Skip to content

Commit 1fe2102

Browse files
source_destination_dict shatters into 4 separate tables (#93)
* source_destination_dict shatters into 4 separate tables * Update tests * 1 more test fix
1 parent 2620cfd commit 1fe2102

File tree

3 files changed

+53
-51
lines changed

3 files changed

+53
-51
lines changed

src/ros_tcp_endpoint/client.py

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,9 @@ def __init__(self, conn, tcp_server, incoming_ip, incoming_port):
3434
Set class variables
3535
Args:
3636
conn:
37-
source_destination_dict: dictionary of destination name to RosCommunicator class
37+
tcp_server: server object
38+
incoming_ip: connected from this IP address
39+
incoming_port: connected from this port
3840
"""
3941
self.conn = conn
4042
self.tcp_server = tcp_server
@@ -149,16 +151,16 @@ def serialize_command(command, params):
149151
return cmd_info + json_info
150152

151153
def send_ros_service_request(self, srv_id, destination, data):
152-
if destination not in self.tcp_server.source_destination_dict.keys():
153-
error_msg = "Service destination '{}' is not registered! Known topics are: {} ".format(
154-
destination, self.tcp_server.source_destination_dict.keys()
154+
if destination not in self.tcp_server.ros_services.keys():
155+
error_msg = "Service destination '{}' is not registered! Known services are: {} ".format(
156+
destination, self.tcp_server.ros_services.keys()
155157
)
156158
self.tcp_server.send_unity_error(error_msg)
157159
rospy.logerr(error_msg)
158160
# TODO: send a response to Unity anyway?
159161
return
160162
else:
161-
ros_communicator = self.tcp_server.source_destination_dict[destination]
163+
ros_communicator = self.tcp_server.ros_services[destination]
162164
service_thread = threading.Thread(
163165
target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator)
164166
)
@@ -179,8 +181,8 @@ def service_call_thread(self, srv_id, destination, data, ros_communicator):
179181

180182
def run(self):
181183
"""
182-
Read a message and determine where to send it based on the source_destination_dict
183-
and destination string. Then send the read message.
184+
Receive a message from Unity and determine where to send it based on the publishers table
185+
and topic string. Then send the read message.
184186
185187
If there is a response after sending the serialized data, assume it is a
186188
ROS service response.
@@ -199,6 +201,7 @@ def run(self):
199201
while not halt_event.is_set():
200202
destination, data = self.read_message(self.conn)
201203

204+
# Process this message that was sent from Unity
202205
if self.tcp_server.pending_srv_id is not None:
203206
# if we've been told that the next message will be a service request/response, process it as such
204207
if self.tcp_server.pending_srv_is_request:
@@ -216,12 +219,12 @@ def run(self):
216219
elif destination.startswith("__"):
217220
# handle a system command, such as registering new topics
218221
self.tcp_server.handle_syscommand(destination, data)
219-
elif destination in self.tcp_server.source_destination_dict:
220-
ros_communicator = self.tcp_server.source_destination_dict[destination]
221-
response = ros_communicator.send(data)
222+
elif destination in self.tcp_server.publishers:
223+
ros_communicator = self.tcp_server.publishers[destination]
224+
ros_communicator.send(data)
222225
else:
223-
error_msg = "Topic '{}' is not registered! Known topics are: {} ".format(
224-
destination, self.tcp_server.source_destination_dict.keys()
226+
error_msg = "Not registered to publish topic '{}'! Valid publish topics are: {} ".format(
227+
destination, self.tcp_server.publishers.keys()
225228
)
226229
self.tcp_server.send_unity_error(error_msg)
227230
rospy.logerr(error_msg)

src/ros_tcp_endpoint/server.py

Lines changed: 21 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -55,16 +55,21 @@ def __init__(self, node_name, buffer_size=1024, connections=2, tcp_ip="", tcp_po
5555
self.unity_tcp_sender = UnityTcpSender()
5656

5757
self.node_name = node_name
58-
self.source_destination_dict = {}
58+
self.publishers = {}
59+
self.subscribers = {}
60+
self.ros_services = {}
61+
self.unity_services = {}
5962
self.buffer_size = buffer_size
6063
self.connections = connections
6164
self.syscommands = SysCommands(self)
6265
self.pending_srv_id = None
6366
self.pending_srv_is_request = False
6467

65-
def start(self, source_destination_dict=None):
66-
if source_destination_dict is not None:
67-
self.source_destination_dict = source_destination_dict
68+
def start(self, publishers=None, subscribers=None):
69+
if publishers is not None:
70+
self.publishers = publishers
71+
if subscribers is not None:
72+
self.subscribers = subscribers
6873
server_thread = threading.Thread(target=self.listen_loop)
6974
# Exit the server thread when the main thread terminates
7075
server_thread.daemon = True
@@ -134,12 +139,10 @@ def subscribe(self, topic, message_name):
134139

135140
rospy.loginfo("RegisterSubscriber({}, {}) OK".format(topic, message_class))
136141

137-
if topic in self.tcp_server.source_destination_dict:
138-
self.tcp_server.source_destination_dict[topic].unregister()
142+
if topic in self.tcp_server.subscribers:
143+
self.tcp_server.subscribers[topic].unregister()
139144

140-
self.tcp_server.source_destination_dict[topic] = RosSubscriber(
141-
topic, message_class, self.tcp_server
142-
)
145+
self.tcp_server.subscribers[topic] = RosSubscriber(topic, message_class, self.tcp_server)
143146

144147
def publish(self, topic, message_name, queue_size=10, latch=False):
145148
if topic == "":
@@ -159,12 +162,10 @@ def publish(self, topic, message_name, queue_size=10, latch=False):
159162

160163
rospy.loginfo("RegisterPublisher({}, {}) OK".format(topic, message_class))
161164

162-
if topic in self.tcp_server.source_destination_dict:
163-
self.tcp_server.source_destination_dict[topic].unregister()
165+
if topic in self.tcp_server.publishers:
166+
self.tcp_server.publishers[topic].unregister()
164167

165-
self.tcp_server.source_destination_dict[topic] = RosPublisher(
166-
topic, message_class, queue_size, latch
167-
)
168+
self.tcp_server.publishers[topic] = RosPublisher(topic, message_class, queue_size, latch)
168169

169170
def ros_service(self, topic, message_name):
170171
if topic == "":
@@ -186,10 +187,10 @@ def ros_service(self, topic, message_name):
186187

187188
rospy.loginfo("RegisterRosService({}, {}) OK".format(topic, message_class))
188189

189-
if topic in self.tcp_server.source_destination_dict:
190-
self.tcp_server.source_destination_dict[topic].unregister()
190+
if topic in self.tcp_server.ros_services:
191+
self.tcp_server.ros_services[topic].unregister()
191192

192-
self.tcp_server.source_destination_dict[topic] = RosService(topic, message_class)
193+
self.tcp_server.ros_services[topic] = RosService(topic, message_class)
193194

194195
def unity_service(self, topic, message_name):
195196
if topic == "":
@@ -211,12 +212,10 @@ def unity_service(self, topic, message_name):
211212

212213
rospy.loginfo("RegisterUnityService({}, {}) OK".format(topic, message_class))
213214

214-
if topic in self.tcp_server.source_destination_dict:
215-
self.tcp_server.source_destination_dict[topic].unregister()
215+
if topic in self.tcp_server.unity_services:
216+
self.tcp_server.unity_services[topic].unregister()
216217

217-
self.tcp_server.source_destination_dict[topic] = UnityService(
218-
topic, message_class, self.tcp_server
219-
)
218+
self.tcp_server.unity_services[topic] = UnityService(topic, message_class, self.tcp_server)
220219

221220
def response(self, srv_id): # the next message is a service response
222221
self.tcp_server.pending_srv_id = srv_id

test/test_server.py

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ def test_unity_service_resolve_message_name_failure():
4949
)
5050
def test_unity_service_resolve_news_service(mock_resolve_message, mock_ros_service):
5151
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
52-
assert server.source_destination_dict == {}
52+
assert server.ros_services == {}
5353
system_cmds = SysCommands(server)
5454
result = system_cmds.unity_service("get_pos", "unity_interfaces.msg/RosUnitySrvMessage")
5555
mock_ros_service.assert_called_once
@@ -64,7 +64,7 @@ def test_unity_service_resolve_news_service(mock_resolve_message, mock_ros_servi
6464
)
6565
def test_unity_service_resolve_existing_service(mock_resolve_message, mock_ros_service):
6666
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
67-
server.source_destination_dict = {"get_pos": mock.Mock()}
67+
server.ros_services = {"get_pos": mock.Mock()}
6868
system_cmds = SysCommands(server)
6969
result = system_cmds.unity_service("get_pos", "unity_interfaces.msg/RosUnitySrvMessage")
7070
mock_ros_service.assert_called_once
@@ -85,31 +85,31 @@ def test_resolve_message_name(mock_import_module, mock_sys_modules):
8585
def test_publish_add_new_topic(mock_ros_publisher):
8686
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
8787
result = SysCommands(server).publish("object_pos_topic", "std_msgs/Bool")
88-
assert server.source_destination_dict != {}
88+
assert server.publishers != {}
8989
mock_ros_publisher.assert_called_once
9090

9191

9292
@mock.patch.object(rospy, "Publisher")
9393
def test_publish_existing_topic(mock_ros_publisher):
9494
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
95-
server.source_destination_dict = {"object_pos_topic": mock.Mock()}
95+
server.publishers = {"object_pos_topic": mock.Mock()}
9696
result = SysCommands(server).publish("object_pos_topic", "std_msgs/Bool")
97-
assert server.source_destination_dict["object_pos_topic"] is not None
97+
assert server.publishers["object_pos_topic"] is not None
9898
mock_ros_publisher.assert_called_once
9999

100100

101101
def test_publish_empty_topic_should_return_none():
102102
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
103103
result = SysCommands(server).publish("", "pos")
104104
assert result is None
105-
assert server.source_destination_dict == {}
105+
assert server.publishers == {}
106106

107107

108108
def test_publish_empty_message_should_return_none():
109109
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
110110
result = SysCommands(server).publish("test-topic", "")
111111
assert result is None
112-
assert server.source_destination_dict == {}
112+
assert server.publishers == {}
113113

114114

115115
@mock.patch.object(rospy, "Subscriber")
@@ -119,7 +119,7 @@ def test_publish_empty_message_should_return_none():
119119
def test_subscribe_to_new_topic(mock_resolve_msg, mock_ros_subscriber):
120120
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
121121
result = SysCommands(server).subscribe("object_pos_topic", "pos")
122-
assert server.source_destination_dict != {}
122+
assert server.subscribers != {}
123123
mock_ros_subscriber.assert_called_once
124124

125125

@@ -129,54 +129,54 @@ def test_subscribe_to_new_topic(mock_resolve_msg, mock_ros_subscriber):
129129
)
130130
def test_subscribe_to_existing_topic(mock_resolve_msg, mock_ros_subscriber):
131131
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
132-
server.source_destination_dict = {"object_pos_topic": mock.Mock()}
132+
server.subscribers = {"object_pos_topic": mock.Mock()}
133133
result = SysCommands(server).subscribe("object_pos_topic", "pos")
134-
assert server.source_destination_dict["object_pos_topic"] is not None
134+
assert server.subscribers["object_pos_topic"] is not None
135135
mock_ros_subscriber.assert_called_once
136136

137137

138138
def test_subscribe_to_empty_topic_should_return_none():
139139
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
140140
result = SysCommands(server).subscribe("", "pos")
141141
assert result is None
142-
assert server.source_destination_dict == {}
142+
assert server.subscribers == {}
143143

144144

145145
def test_subscribe_to_empty_message_should_return_none():
146146
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
147147
result = SysCommands(server).subscribe("test-topic", "")
148148
assert result is None
149-
assert server.source_destination_dict == {}
149+
assert server.subscribers == {}
150150

151151

152152
@mock.patch.object(rospy, "ServiceProxy")
153153
@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name")
154154
def test_ros_service_new_topic(mock_resolve_msg, mock_ros_service):
155155
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
156156
result = SysCommands(server).ros_service("object_pos_topic", "pos")
157-
assert server.source_destination_dict != {}
157+
assert server.ros_services != {}
158158
mock_ros_service.assert_called_once
159159

160160

161161
@mock.patch.object(rospy, "ServiceProxy")
162162
@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name")
163163
def test_ros_service_existing_topic(mock_resolve_msg, mock_ros_service):
164164
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
165-
server.source_destination_dict = {"object_pos_topic": mock.Mock()}
165+
server.ros_services = {"object_pos_topic": mock.Mock()}
166166
result = SysCommands(server).ros_service("object_pos_topic", "pos")
167-
assert server.source_destination_dict["object_pos_topic"] is not None
167+
assert server.ros_services["object_pos_topic"] is not None
168168
mock_ros_service.assert_called_once
169169

170170

171171
def test_ros_service_empty_topic_should_return_none():
172172
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
173173
result = SysCommands(server).ros_service("", "pos")
174174
assert result is None
175-
assert server.source_destination_dict == {}
175+
assert server.ros_services == {}
176176

177177

178178
def test_ros_service_empty_message_should_return_none():
179179
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
180180
result = SysCommands(server).ros_service("test-topic", "")
181181
assert result is None
182-
assert server.source_destination_dict == {}
182+
assert server.ros_services == {}

0 commit comments

Comments
 (0)