Skip to content

Commit c7e3ece

Browse files
AIRO-1617 Private ros params (#123)
* made ros params private * added default to ros parameter tcp_ip * set server default address to 0.0.0.0
1 parent 58cd28f commit c7e3ece

File tree

4 files changed

+14
-11
lines changed

4 files changed

+14
-11
lines changed

config/params.yaml

Lines changed: 0 additions & 1 deletion
This file was deleted.

launch/endpoint.launch

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,9 @@
11
<launch>
2-
<rosparam file="$(find ros_tcp_endpoint)/config/params.yaml" command="load"/>
3-
<node name="server_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" args="--wait" output="screen" respawn="true" />
4-
</launch>
2+
<arg name="tcp_ip" default="0.0.0.0"/>
3+
<arg name="tcp_port" default="10000"/>
4+
5+
<node name="unity_endpoint" pkg="ros_tcp_endpoint" type="default_server_endpoint.py" output="screen">
6+
<param name="tcp_ip" type="string" value="$(arg tcp_ip)"/>
7+
<param name="tcp_port" type="int" value="$(arg tcp_port)"/>
8+
</node>
9+
</launch>

src/ros_tcp_endpoint/default_server_endpoint.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,9 @@
66

77

88
def main(args=None):
9-
tcp_server = TcpServer("UnityEndpoint")
10-
119
# Start the Server Endpoint
12-
rospy.init_node(tcp_server.node_name, anonymous=True)
10+
rospy.init_node("unity_endpoint", anonymous=True)
11+
tcp_server = TcpServer(rospy.get_name())
1312
tcp_server.start()
1413
rospy.spin()
1514

src/ros_tcp_endpoint/server.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,16 +43,16 @@ def __init__(self, node_name, buffer_size=1024, connections=10, tcp_ip=None, tcp
4343
connections: Max number of queued connections. See Python Socket documentation
4444
"""
4545
if tcp_ip:
46-
self.loginfo("Using ROS_IP override from constructor: {}".format(tcp_ip))
46+
self.loginfo("Using 'tcp_ip' override from constructor: {}".format(tcp_ip))
4747
self.tcp_ip = tcp_ip
4848
else:
49-
self.tcp_ip = rospy.get_param("/ROS_IP")
49+
self.tcp_ip = rospy.get_param("~tcp_ip", "0.0.0.0")
5050

5151
if tcp_port:
52-
self.loginfo("Using ROS_TCP_PORT override from constructor: {}".format(tcp_port))
52+
self.loginfo("Using 'tcp_port' override from constructor: {}".format(tcp_port))
5353
self.tcp_port = tcp_port
5454
else:
55-
self.tcp_port = rospy.get_param("/ROS_TCP_PORT", 10000)
55+
self.tcp_port = rospy.get_param("~tcp_port", 10000)
5656

5757
self.unity_tcp_sender = UnityTcpSender(self)
5858

0 commit comments

Comments
 (0)