Skip to content

Commit eedcfe3

Browse files
Fixes for Python 2
1 parent aac8042 commit eedcfe3

File tree

5 files changed

+5
-5
lines changed

5 files changed

+5
-5
lines changed

src/ros_tcp_endpoint/default_server_endpoint.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ def main(args=None):
99
tcp_server = TcpServer("UnityEndpoint")
1010

1111
# Start the Server Endpoint
12-
rospy.init_node(ros_node_name, anonymous=True)
12+
rospy.init_node(tcp_server.node_name, anonymous=True)
1313
tcp_server.start()
1414
rospy.spin()
1515

src/ros_tcp_endpoint/publisher.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ def __init__(self, topic, message_class, queue_size=10, latch=False):
3232
queue_size: Max number of entries to maintain in an outgoing queue
3333
"""
3434
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
35-
node_name = f"{strippedTopic}_RosPublisher"
35+
node_name = "{}_RosPublisher".format(strippedTopic)
3636
RosSender.__init__(self, node_name)
3737
self.msg = message_class()
3838
self.pub = rospy.Publisher(topic, message_class, queue_size=queue_size, latch=latch)

src/ros_tcp_endpoint/service.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ def __init__(self, service, service_class):
3131
service_class: The service class in catkin workspace
3232
"""
3333
strippedService = re.sub("[^A-Za-z0-9_]+", "", service)
34-
node_name = f"{strippedService}_RosService"
34+
node_name = "{}_RosService".format(strippedService)
3535
RosSender.__init__(self, node_name)
3636

3737
self.srv_class = service_class._request_class()

src/ros_tcp_endpoint/subscriber.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ def __init__(self, topic, message_class, tcp_server, queue_size=10):
3434
queue_size: Max number of entries to maintain in an outgoing queue
3535
"""
3636
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
37-
self.node_name = f"{strippedTopic}_RosSubscriber"
37+
self.node_name = "{}_RosSubscriber".format(strippedTopic)
3838
RosReceiver.__init__(self, self.node_name)
3939
self.topic = topic
4040
self.msg = message_class

src/ros_tcp_endpoint/unity_service.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ def __init__(self, topic, service_class, tcp_server, queue_size=10):
3434
queue_size: Max number of entries to maintain in an outgoing queue
3535
"""
3636
strippedTopic = re.sub("[^A-Za-z0-9_]+", "", topic)
37-
node_name = f"{strippedTopic}_service"
37+
node_name = "{}_service".format(strippedTopic)
3838

3939
self.topic = topic
4040
self.service_class = service_class

0 commit comments

Comments
 (0)