33 """Defines the main method for the nmea_topic_serial_reader executable.""" 37 from nmea_msgs.msg
import Sentence
44 """Create and run the nmea_topic_serial_reader ROS node. 46 Opens a serial device and publishes data from the device as nmea_msgs.msg.Sentence messages. 49 ~port (str): Path of the serial device to open. 50 ~baud (int): Baud rate to configure the serial device. 53 nmea_sentence (nmea_msgs.msg.Sentence): Publishes each line from the open serial device as a new 54 message. The header's stamp is set to the rostime when the data is read from the serial device. 56 rospy.init_node(
'nmea_topic_serial_reader')
58 nmea_pub = rospy.Publisher(
"nmea_sentence", Sentence)
60 serial_port = rospy.get_param(
'~port',
'/dev/ttyUSB0')
61 serial_baud = rospy.get_param(
'~baud', 4800)
64 frame_id = RosNMEADriver.get_frame_id()
67 GPS = serial.Serial(port=serial_port, baudrate=serial_baud, timeout=2)
68 while not rospy.is_shutdown():
69 data = GPS.readline().strip()
72 sentence.header.stamp = rospy.get_rostime()
73 sentence.header.frame_id = frame_id
74 sentence.sentence = data
76 nmea_pub.publish(sentence)
78 except rospy.ROSInterruptException: