serial_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
35 
36 __author__ = "mferguson@willowgarage.com (Michael Ferguson)"
37 
38 import rospy
39 from rosserial_python import SerialClient, RosSerialServer
40 from serial import SerialException
41 from time import sleep
42 import multiprocessing
43 
44 import sys
45 
46 if __name__=="__main__":
47 
48  rospy.init_node("serial_node")
49  rospy.loginfo("ROS Serial Python Node")
50 
51  port_name = rospy.get_param('~port','/dev/ttyUSB0')
52  baud = int(rospy.get_param('~baud','57600'))
53 
54  # for systems where pyserial yields errors in the fcntl.ioctl(self.fd, TIOCMBIS, \
55  # TIOCM_DTR_str) line, which causes an IOError, when using simulated port
56  fix_pyserial_for_test = rospy.get_param('~fix_pyserial_for_test', False)
57 
58  # TODO: should these really be global?
59  tcp_portnum = int(rospy.get_param('/rosserial_embeddedlinux/tcp_port', '11411'))
60  fork_server = rospy.get_param('/rosserial_embeddedlinux/fork_server', False)
61 
62  # TODO: do we really want command line params in addition to parameter server params?
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])
68 
69  if port_name == "tcp" :
70  server = RosSerialServer(tcp_portnum, fork_server)
71  rospy.loginfo("Waiting for socket connections on port %d" % tcp_portnum)
72  try:
73  server.listen()
74  except KeyboardInterrupt:
75  rospy.loginfo("got keyboard interrupt")
76  finally:
77  rospy.loginfo("Shutting down")
78  for process in multiprocessing.active_children():
79  rospy.loginfo("Shutting down process %r", process)
80  process.terminate()
81  process.join()
82  rospy.loginfo("All done")
83 
84  else : # Use serial port
85  while not rospy.is_shutdown():
86  rospy.loginfo("Connecting to %s at %d baud" % (port_name,baud) )
87  try:
88  client = SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test)
89  client.run()
90  except KeyboardInterrupt:
91  break
92  except SerialException:
93  sleep(1.0)
94  continue
95  except OSError:
96  sleep(1.0)
97  continue
98  except:
99  rospy.logwarn("Unexpected Error.%s", sys.exc_info()[0])
100  client.port.close()
101  sleep(1.0)
102  continue
103 


rosserial_python
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 23:35:28