33 """Defines the main method for the nmea_serial_driver executable.""" 44 """Create and run the nmea_serial_driver ROS node. 46 Creates a ROS NMEA Driver and feeds it NMEA sentence strings from a serial device. 49 ~port (str): Path of the serial device to open. 50 ~baud (int): Baud rate to configure the serial device. 52 rospy.init_node(
'nmea_serial_driver')
54 serial_port = rospy.get_param(
'~port',
'/dev/ttyUSB0')
55 serial_baud = rospy.get_param(
'~baud', 4800)
56 frame_id = RosNMEADriver.get_frame_id()
59 GPS = serial.Serial(port=serial_port, baudrate=serial_baud, timeout=2)
63 while not rospy.is_shutdown():
64 data = GPS.readline().strip()
66 driver.add_sentence(data, frame_id)
67 except ValueError
as e:
69 "Value error, likely due to missing fields in the NMEA message. " 70 "Error was: %s. Please report this issue at " 71 "github.com/ros-drivers/nmea_navsat_driver, including a bag file with the NMEA " 72 "sentences that caused it." %
75 except (rospy.ROSInterruptException, serial.serialutil.SerialException):
77 except serial.SerialException
as ex:
79 "Could not open serial port: I/O error({0}): {1}".format(ex.errno, ex.strerror))