36 __author__ =
"mferguson@willowgarage.com (Michael Ferguson)" 39 from rosserial_python
import SerialClient, RosSerialServer
40 from serial
import SerialException
41 from time
import sleep
42 import multiprocessing
46 if __name__==
"__main__":
48 rospy.init_node(
"serial_node")
49 rospy.loginfo(
"ROS Serial Python Node")
51 port_name = rospy.get_param(
'~port',
'/dev/ttyUSB0')
52 baud = int(rospy.get_param(
'~baud',
'57600'))
56 fix_pyserial_for_test = rospy.get_param(
'~fix_pyserial_for_test',
False)
59 tcp_portnum = int(rospy.get_param(
'/rosserial_embeddedlinux/tcp_port',
'11411'))
60 fork_server = rospy.get_param(
'/rosserial_embeddedlinux/fork_server',
False)
63 sys.argv = rospy.myargv(argv=sys.argv)
64 if len(sys.argv) >= 2 :
65 port_name = sys.argv[1]
66 if len(sys.argv) == 3 :
67 tcp_portnum = int(sys.argv[2])
69 if port_name ==
"tcp" :
70 server = RosSerialServer(tcp_portnum, fork_server)
71 rospy.loginfo(
"Waiting for socket connections on port %d" % tcp_portnum)
74 except KeyboardInterrupt:
75 rospy.loginfo(
"got keyboard interrupt")
77 rospy.loginfo(
"Shutting down")
78 for process
in multiprocessing.active_children():
79 rospy.loginfo(
"Shutting down process %r", process)
82 rospy.loginfo(
"All done")
85 while not rospy.is_shutdown():
86 rospy.loginfo(
"Connecting to %s at %d baud" % (port_name,baud) )
88 client = SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test)
90 except KeyboardInterrupt:
92 except SerialException: