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__":
47 rospy.init_node(
"serial_node")
48 rospy.loginfo(
"ROS Serial Python Node")
50 port_name = rospy.get_param(
'~port',
'/dev/ttyUSB0')
51 baud = int(rospy.get_param(
'~baud',
'57600'))
55 fix_pyserial_for_test = rospy.get_param(
'~fix_pyserial_for_test',
False)
59 if(rospy.has_param(
'~tcp_port')):
60 tcp_portnum = int(rospy.get_param(
'~tcp_port'))
62 tcp_portnum = int(rospy.get_param(
'/rosserial_embeddedlinux/tcp_port',
'11411'))
64 if(rospy.has_param(
'~fork_server')):
65 fork_server = rospy.get_param(
'~fork_server')
67 fork_server = rospy.get_param(
'/rosserial_embeddedlinux/fork_server',
False)
70 sys.argv = rospy.myargv(argv=sys.argv)
71 if len(sys.argv) >= 2 :
72 port_name = sys.argv[1]
73 if len(sys.argv) == 3 :
74 tcp_portnum = int(sys.argv[2])
76 if port_name ==
"tcp" :
78 rospy.loginfo(
"Waiting for socket connections on port %d" % tcp_portnum)
81 except KeyboardInterrupt:
82 rospy.loginfo(
"got keyboard interrupt")
84 rospy.loginfo(
"Shutting down")
85 for process
in multiprocessing.active_children():
86 rospy.loginfo(
"Shutting down process %r", process)
89 rospy.loginfo(
"All done")
92 while not rospy.is_shutdown():
93 rospy.loginfo(
"Connecting to %s at %d baud" % (port_name,baud) )
95 client =
SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test)
97 except KeyboardInterrupt:
99 except SerialException:
106 rospy.logwarn(
"Unexpected Error: %s", sys.exc_info()[0])