Skip to content

Commit

Permalink
Add optional private parameter config to Python server (ros-drivers#562)
Browse files Browse the repository at this point in the history
* 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
  • Loading branch information
amalpavithran authored Jun 16, 2021
1 parent a5180dc commit c169ae2
Showing 1 changed file with 11 additions and 3 deletions.
14 changes: 11 additions & 3 deletions rosserial_python/nodes/serial_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down

0 comments on commit c169ae2

Please sign in to comment.