serial_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
35 
36 import rospy
37 from rosserial_arduino import SerialClient
38 from serial import SerialException
39 from time import sleep
40 
41 import sys
42 
43 if __name__=="__main__":
44 
45  rospy.init_node("serial_node")
46  rospy.loginfo("ROS Serial Python Node")
47 
48  port_name = rospy.get_param('~port','/dev/ttyUSB0')
49  baud = int(rospy.get_param('~baud','57600'))
50 
51  # Number of seconds of sync failure after which Arduino is auto-reset.
52  # 0 = no timeout, auto-reset disabled
53  auto_reset_timeout = int(rospy.get_param('~auto_reset_timeout','0'))
54 
55  # for systems where pyserial yields errors in the fcntl.ioctl(self.fd, TIOCMBIS, \
56  # TIOCM_DTR_str) line, which causes an IOError, when using simulated port
57  fix_pyserial_for_test = rospy.get_param('~fix_pyserial_for_test', False)
58 
59  # TODO: do we really want command line params in addition to parameter server params?
60  sys.argv = rospy.myargv(argv=sys.argv)
61  if len(sys.argv) >= 2 :
62  port_name = sys.argv[1]
63 
64  while not rospy.is_shutdown():
65  rospy.loginfo("Connecting to %s at %d baud" % (port_name, baud))
66  try:
67  client = SerialClient(port_name, baud, fix_pyserial_for_test=fix_pyserial_for_test, auto_reset_timeout=auto_reset_timeout)
68  client.run()
69  except KeyboardInterrupt:
70  break
71  except SerialException:
72  sleep(1.0)
73  continue
74  except OSError:
75  sleep(1.0)
76  continue


rosserial_arduino
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Mon Feb 28 2022 23:35:30