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  rospy.init_node("serial_node")
48  rospy.loginfo("ROS Serial Python Node")
49 
50  port_name = rospy.get_param('~port','/dev/ttyUSB0')
51  baud = int(rospy.get_param('~baud','57600'))
52 
53  # for systems where pyserial yields errors in the fcntl.ioctl(self.fd, TIOCMBIS, \
54  # TIOCM_DTR_str) line, which causes an IOError, when using simulated port
55  fix_pyserial_for_test = rospy.get_param('~fix_pyserial_for_test', False)
56 
57  # Allows for assigning local parameters for tcp_port and fork_server with
58  # global parameters as fallback to prevent breaking changes
59  if(rospy.has_param('~tcp_port')):
60  tcp_portnum = int(rospy.get_param('~tcp_port'))
61  else:
62  tcp_portnum = int(rospy.get_param('/rosserial_embeddedlinux/tcp_port', '11411'))
63 
64  if(rospy.has_param('~fork_server')):
65  fork_server = rospy.get_param('~fork_server')
66  else:
67  fork_server = rospy.get_param('/rosserial_embeddedlinux/fork_server', False)
68 
69  # TODO: do we really want command line params in addition to parameter server params?
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])
75 
76  if port_name == "tcp" :
77  server = RosSerialServer(tcp_portnum, fork_server)
78  rospy.loginfo("Waiting for socket connections on port %d" % tcp_portnum)
79  try:
80  server.listen()
81  except KeyboardInterrupt:
82  rospy.loginfo("got keyboard interrupt")
83  finally:
84  rospy.loginfo("Shutting down")
85  for process in multiprocessing.active_children():
86  rospy.loginfo("Shutting down process %r", process)
87  process.terminate()
88  process.join()
89  rospy.loginfo("All done")
90 
91  else : # Use serial port
92  while not rospy.is_shutdown():
93  rospy.loginfo("Connecting to %s at %d baud" % (port_name,baud) )
94  try:
95  client = SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test)
96  client.run()
97  except KeyboardInterrupt:
98  break
99  except SerialException:
100  sleep(1.0)
101  continue
102  except OSError:
103  sleep(1.0)
104  continue
105  except:
106  rospy.logwarn("Unexpected Error: %s", sys.exc_info()[0])
107  client.port.close()
108  sleep(1.0)
109  continue
rosserial_python.SerialClient.SerialClient
Definition: SerialClient.py:319
rosserial_python.SerialClient.RosSerialServer
Definition: SerialClient.py:214


rosserial_python
Author(s): Michael Ferguson
autogenerated on Wed Mar 2 2022 00:58:10