Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 __author__ = "mferguson@willowgarage.com (Michael Ferguson)"
00037
00038 import roslib; roslib.load_manifest("rosserial_python")
00039 import rospy
00040 from rosserial_python import SerialClient, RosSerialServer
00041 import multiprocessing
00042
00043 import sys
00044
00045 if __name__=="__main__":
00046
00047 port_name = rospy.get_param('~port','/dev/ttyUSB0')
00048 baud = int(rospy.get_param('~baud','57600'))
00049 tcp_portnum = int(rospy.get_param('/rosserial_embeddedlinux/tcp_port', '11411'))
00050 fork_server = rospy.get_param('/rosserial_embeddedlinux/fork_server', True)
00051
00052 sys.argv = rospy.myargv(argv=sys.argv)
00053
00054
00055 if len(sys.argv) == 2 :
00056 port_name = sys.argv[1]
00057 if len(sys.argv) == 3 :
00058 tcp_portnum = int(sys.argv[2])
00059
00060 if port_name == "tcp" :
00061 server = RosSerialServer(tcp_portnum, fork_server)
00062 rospy.loginfo("Waiting for socket connections on port %d" % tcp_portnum)
00063 try:
00064 server.listen()
00065 except KeyboardInterrupt:
00066 rospy.loginfo("got keyboard interrupt")
00067 finally:
00068 rospy.loginfo("Shutting down")
00069 for process in multiprocessing.active_children():
00070 rospy.loginfo("Shutting down process %r", process)
00071 process.terminate()
00072 process.join()
00073 rospy.loginfo("All done")
00074
00075 else :
00076 rospy.init_node("serial_node")
00077 rospy.loginfo("ROS Serial Python Node")
00078 rospy.loginfo("Connected on %s at %d baud" % (port_name,baud) )
00079 client = SerialClient(port_name, baud)
00080 try:
00081 client.run()
00082 except KeyboardInterrupt:
00083 pass
00084