Skip to content

Commit df24eeb

Browse files
Update from Ros1 + auto format
2 parents e6a7dcd + bf5135f commit df24eeb

File tree

4 files changed

+48
-53
lines changed

4 files changed

+48
-53
lines changed

ros_tcp_endpoint/service.py

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -24,21 +24,21 @@ class RosService(RosSender):
2424
"""
2525
Class to send messages to a ROS service.
2626
"""
27+
2728
def __init__(self, service, service_class):
2829
"""
2930
Args:
3031
service: The service name in ROS
3132
service_class: The service class in catkin workspace
3233
"""
33-
strippedService = re.sub('[^A-Za-z0-9_]+', '', service)
34-
node_name = f'{strippedService}_RosService'
34+
strippedService = re.sub("[^A-Za-z0-9_]+", "", service)
35+
node_name = f"{strippedService}_RosService"
3536
RosSender.__init__(self, node_name)
36-
37+
3738
self.service_topic = service
3839
self.cli = self.create_client(service_class, service)
3940
self.req = service_class.Request()
4041

41-
4242
def send(self, data):
4343
"""
4444
Takes in serialized message data from source outside of the ROS network,
@@ -55,9 +55,11 @@ def send(self, data):
5555
message = deserialize_message(data, message_type)
5656

5757
if not self.cli.service_is_ready():
58-
self.get_logger().error('Ignoring service call to {} - service is not ready.'.format(self.service_topic))
58+
self.get_logger().error(
59+
"Ignoring service call to {} - service is not ready.".format(self.service_topic)
60+
)
5961
return None
60-
62+
6163
self.future = self.cli.call_async(message)
6264

6365
while rclpy.ok():
@@ -66,13 +68,12 @@ def send(self, data):
6668
response = self.future.result()
6769
return response
6870
except Exception as e:
69-
self.get_logger().info(f'Service call failed {e}')
71+
self.get_logger().info(f"Service call failed {e}")
7072

7173
break
7274

7375
return None
7476

75-
7677
def unregister(self):
7778
"""
7879

ros_tcp_endpoint/subscriber.py

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,8 @@ def __init__(self, topic, message_class, tcp_server, queue_size=10):
3535
message_class: The message class in catkin workspace
3636
queue_size: Max number of entries to maintain in an outgoing queue
3737
"""
38-
strippedTopic = re.sub('[^A-Za-z0-9_]+', '', topic)
39-
self.node_name = f'{strippedTopic}_RosSubscriber'
38+
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
39+
self.node_name = f"{strippedTopic}_RosSubscriber"
4040
RosReceiver.__init__(self, self.node_name)
4141
self.topic = topic
4242
self.msg = message_class
@@ -47,10 +47,7 @@ def __init__(self, topic, message_class, tcp_server, queue_size=10):
4747

4848
# Start Subscriber listener function
4949
self.subscription = self.create_subscription(
50-
self.msg,
51-
self.topic,
52-
self.send,
53-
qos_profile #queue_size
50+
self.msg, self.topic, self.send, qos_profile # queue_size
5451
)
5552
self.subscription
5653

@@ -74,4 +71,4 @@ def unregister(self):
7471
7572
"""
7673
self.destroy_subscription(self.subscription)
77-
self.destroy_node()
74+
self.destroy_node()

test/test_server.py

Lines changed: 26 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
from unittest import mock
22
from ros_tcp_endpoint import TcpServer
33
from ros_tcp_endpoint.server import SysCommands
4-
from ros_tcp_endpoint.server import resolve_message_name
54
import importlib
65
import rospy
76
import sys
@@ -16,14 +15,14 @@ def test_server_constructor(mock_ros, mock_socket):
1615
assert server.node_name == "test-tcp-server"
1716
assert server.tcp_ip == "127.0.0.1"
1817
assert server.buffer_size == 1024
19-
assert server.connections == 2
18+
assert server.connections == 10
2019

2120

2221
def test_start_server():
2322
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
2423
assert server.tcp_ip == "127.0.0.1"
2524
assert server.tcp_port == 10000
26-
assert server.connections == 2
25+
assert server.connections == 10
2726
server.start()
2827

2928

@@ -43,13 +42,11 @@ def test_unity_service_resolve_message_name_failure():
4342

4443
@mock.patch.object(rospy, "Service")
4544
@mock.patch.object(
46-
ros_tcp_endpoint.server,
47-
"resolve_message_name",
48-
return_value="unity_interfaces.msg/RosUnitySrvMessage",
45+
SysCommands, "resolve_message_name", return_value="unity_interfaces.msg/RosUnitySrvMessage"
4946
)
5047
def test_unity_service_resolve_news_service(mock_resolve_message, mock_ros_service):
5148
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
52-
assert server.ros_services == {}
49+
assert server.ros_services_table == {}
5350
system_cmds = SysCommands(server)
5451
result = system_cmds.unity_service("get_pos", "unity_interfaces.msg/RosUnitySrvMessage")
5552
mock_ros_service.assert_called_once
@@ -58,9 +55,7 @@ def test_unity_service_resolve_news_service(mock_resolve_message, mock_ros_servi
5855

5956
@mock.patch.object(rospy, "Service")
6057
@mock.patch.object(
61-
ros_tcp_endpoint.server,
62-
"resolve_message_name",
63-
return_value="unity_interfaces.msg/RosUnitySrvMessage",
58+
SysCommands, "resolve_message_name", return_value="unity_interfaces.msg/RosUnitySrvMessage"
6459
)
6560
def test_unity_service_resolve_existing_service(mock_resolve_message, mock_ros_service):
6661
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
@@ -74,8 +69,9 @@ def test_unity_service_resolve_existing_service(mock_resolve_message, mock_ros_s
7469
@mock.patch.object(sys, "modules", return_value="unity_interfaces.msg")
7570
@mock.patch.object(importlib, "import_module")
7671
def test_resolve_message_name(mock_import_module, mock_sys_modules):
72+
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
7773
msg_name = "unity_interfaces.msg/UnityColor.msg"
78-
result = resolve_message_name(msg_name)
74+
result = SysCommands(server).resolve_message_name(msg_name)
7975
mock_import_module.assert_called_once
8076
mock_sys_modules.assert_called_once
8177
assert result is not None
@@ -85,98 +81,94 @@ def test_resolve_message_name(mock_import_module, mock_sys_modules):
8581
def test_publish_add_new_topic(mock_ros_publisher):
8682
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
8783
result = SysCommands(server).publish("object_pos_topic", "std_msgs/Bool")
88-
assert server.publishers != {}
84+
assert server.publishers_table != {}
8985
mock_ros_publisher.assert_called_once
9086

9187

9288
@mock.patch.object(rospy, "Publisher")
9389
def test_publish_existing_topic(mock_ros_publisher):
9490
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
95-
server.publishers = {"object_pos_topic": mock.Mock()}
91+
server.publishers_table = {"object_pos_topic": mock.Mock()}
9692
result = SysCommands(server).publish("object_pos_topic", "std_msgs/Bool")
97-
assert server.publishers["object_pos_topic"] is not None
93+
assert server.publishers_table["object_pos_topic"] is not None
9894
mock_ros_publisher.assert_called_once
9995

10096

10197
def test_publish_empty_topic_should_return_none():
10298
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
10399
result = SysCommands(server).publish("", "pos")
104100
assert result is None
105-
assert server.publishers == {}
101+
assert server.publishers_table == {}
106102

107103

108104
def test_publish_empty_message_should_return_none():
109105
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
110106
result = SysCommands(server).publish("test-topic", "")
111107
assert result is None
112-
assert server.publishers == {}
108+
assert server.publishers_table == {}
113109

114110

115111
@mock.patch.object(rospy, "Subscriber")
116-
@mock.patch.object(
117-
ros_tcp_endpoint.server, "resolve_message_name", return_value="unity_interfaces.msg/Pos"
118-
)
112+
@mock.patch.object(SysCommands, "resolve_message_name", return_value="unity_interfaces.msg/Pos")
119113
def test_subscribe_to_new_topic(mock_resolve_msg, mock_ros_subscriber):
120114
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
121115
result = SysCommands(server).subscribe("object_pos_topic", "pos")
122-
assert server.subscribers != {}
116+
assert server.subscribers_table != {}
123117
mock_ros_subscriber.assert_called_once
124118

125119

126120
@mock.patch.object(rospy, "Subscriber")
127-
@mock.patch.object(
128-
ros_tcp_endpoint.server, "resolve_message_name", return_value="unity_interfaces.msg/Pos"
129-
)
121+
@mock.patch.object(SysCommands, "resolve_message_name", return_value="unity_interfaces.msg/Pos")
130122
def test_subscribe_to_existing_topic(mock_resolve_msg, mock_ros_subscriber):
131123
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
132-
server.subscribers = {"object_pos_topic": mock.Mock()}
124+
server.subscribers_table = {"object_pos_topic": mock.Mock()}
133125
result = SysCommands(server).subscribe("object_pos_topic", "pos")
134-
assert server.subscribers["object_pos_topic"] is not None
126+
assert server.subscribers_table["object_pos_topic"] is not None
135127
mock_ros_subscriber.assert_called_once
136128

137129

138130
def test_subscribe_to_empty_topic_should_return_none():
139131
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
140132
result = SysCommands(server).subscribe("", "pos")
141133
assert result is None
142-
assert server.subscribers == {}
134+
assert server.subscribers_table == {}
143135

144136

145137
def test_subscribe_to_empty_message_should_return_none():
146138
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
147139
result = SysCommands(server).subscribe("test-topic", "")
148140
assert result is None
149-
assert server.subscribers == {}
141+
assert server.subscribers_table == {}
150142

151143

152144
@mock.patch.object(rospy, "ServiceProxy")
153-
@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name")
145+
@mock.patch.object(SysCommands, "resolve_message_name")
154146
def test_ros_service_new_topic(mock_resolve_msg, mock_ros_service):
155147
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
156148
result = SysCommands(server).ros_service("object_pos_topic", "pos")
157-
assert server.ros_services != {}
149+
assert server.ros_services_table != {}
158150
mock_ros_service.assert_called_once
159151

160152

161153
@mock.patch.object(rospy, "ServiceProxy")
162-
@mock.patch.object(ros_tcp_endpoint.server, "resolve_message_name")
154+
@mock.patch.object(SysCommands, "resolve_message_name")
163155
def test_ros_service_existing_topic(mock_resolve_msg, mock_ros_service):
164156
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
165-
server.ros_services = {"object_pos_topic": mock.Mock()}
157+
server.ros_services_table = {"object_pos_topic": mock.Mock()}
166158
result = SysCommands(server).ros_service("object_pos_topic", "pos")
167-
assert server.ros_services["object_pos_topic"] is not None
159+
assert server.ros_services_table["object_pos_topic"] is not None
168160
mock_ros_service.assert_called_once
169161

170162

171163
def test_ros_service_empty_topic_should_return_none():
172164
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
173165
result = SysCommands(server).ros_service("", "pos")
174166
assert result is None
175-
assert server.ros_services == {}
167+
assert server.ros_services_table == {}
176168

177169

178170
def test_ros_service_empty_message_should_return_none():
179171
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
180172
result = SysCommands(server).ros_service("test-topic", "")
181173
assert result is None
182-
assert server.ros_services == {}
174+
assert server.ros_services_table == {}

test/test_tcp_sender.py

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,14 @@
11
import queue
22
import socket
33
from unittest import mock
4+
from ros_tcp_endpoint import TcpServer
45
import ros_tcp_endpoint
56

67

78
@mock.patch("ros_tcp_endpoint.tcp_sender.rospy")
89
def test_tcp_sender_constructor(mock_ros):
9-
tcp_sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender()
10+
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
11+
tcp_sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender(server)
1012
assert tcp_sender.sender_id == 1
1113
assert tcp_sender.time_between_halt_checks == 5
1214
assert tcp_sender.queue == None
@@ -26,7 +28,8 @@ def test_tcp_sender_constructor(mock_ros):
2628

2729
@mock.patch.object(ros_tcp_endpoint.client.ClientThread, "serialize_message")
2830
def test_send_message_should_serialize_message(mock_serialize_msg):
29-
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender()
31+
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
32+
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender(server)
3033
sender.queue = queue.Queue()
3134
sender.send_unity_message("test topic", "test msg")
3235
mock_serialize_msg.assert_called_once()
@@ -44,15 +47,17 @@ def test_send_message_should_serialize_message(mock_serialize_msg):
4447

4548
@mock.patch("ros_tcp_endpoint.thread_pauser.ThreadPauser")
4649
def test_send_unity_service_response_should_resume(mock_thread_pauser_class):
47-
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender()
50+
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
51+
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender(server)
4852
thread_pauser = mock_thread_pauser_class()
4953
sender.services_waiting = {"moveit": thread_pauser}
5054
sender.send_unity_service_response("moveit", "test data")
5155
thread_pauser.resume_with_result.assert_called_once()
5256

5357

5458
def test_start_sender_should_increase_sender_id():
55-
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender()
59+
server = TcpServer(node_name="test-tcp-server", tcp_ip="127.0.0.1", tcp_port=10000)
60+
sender = ros_tcp_endpoint.tcp_sender.UnityTcpSender(server)
5661
init_sender_id = 1
5762
assert sender.sender_id == init_sender_id
5863
sender.start_sender(mock.Mock(), mock.Mock())

0 commit comments

Comments
 (0)