From c169ae2173dcfda7cee567d64beae45198459400 Mon Sep 17 00:00:00 2001 From: Amal Pavithran Date: Wed, 16 Jun 2021 20:04:19 +0530 Subject: [PATCH] Add optional private parameter config to Python server (#562) * Made tcp_port a local parameter The tcp_port parameter being a global parameter prevents the launch of multiple serial nodes on different port numbers using a launch file * Added Fallback & Modified fork_server parameter * Removed unnecessary defaults & added comments --- rosserial_python/nodes/serial_node.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/rosserial_python/nodes/serial_node.py b/rosserial_python/nodes/serial_node.py index f9048c93d..ddbcf8328 100755 --- a/rosserial_python/nodes/serial_node.py +++ b/rosserial_python/nodes/serial_node.py @@ -54,9 +54,17 @@ # TIOCM_DTR_str) line, which causes an IOError, when using simulated port fix_pyserial_for_test = rospy.get_param('~fix_pyserial_for_test', False) - # TODO: should these really be global? - tcp_portnum = int(rospy.get_param('/rosserial_embeddedlinux/tcp_port', '11411')) - fork_server = rospy.get_param('/rosserial_embeddedlinux/fork_server', False) + # Allows for assigning local parameters for tcp_port and fork_server with + # global parameters as fallback to prevent breaking changes + if(rospy.has_param('~tcp_port')): + tcp_portnum = int(rospy.get_param('~tcp_port')) + else: + tcp_portnum = int(rospy.get_param('/rosserial_embeddedlinux/tcp_port', '11411')) + + if(rospy.has_param('~fork_server')): + fork_server = rospy.get_param('~fork_server') + else: + fork_server = rospy.get_param('/rosserial_embeddedlinux/fork_server', False) # TODO: do we really want command line params in addition to parameter server params? sys.argv = rospy.myargv(argv=sys.argv)