Overview

This package provides a ROS interface for GPS devices that output compatible NMEA sentences. See the GPSD documentation of NMEA sentences for details on the raw format. Of the thousands of NMEA-compatible GPS devices, we are compiling a list of devices known to be supported.

This package is compatible with the geographic_info project as well as any other nodes that support sensor_msgs/NavSatFix and/or sensor_msgs/TimeReference.

Due to the dependency on sensor_msgs/TimeReference, this package is only compatible with ROS Fuerte or newer.

No C++ or Python API is provided, only a ROS API.

Sample Usage

To get up and running quickly, you can use the following command to start outputting your GPS data onto ROS topics. This assumes your GPS is outputting GGA NMEA sentences, is connected to /dev/ttyUSB0 and is communicating at 38400 baud.

$ rosrun nmea_gps_driver nmea_serial_driver.py _port:=/dev/ttyUSB0 _baud:=38400

Roadmap

  • Add support for additional NMEA sentences beyond GSA, RMC and GGA. Specific requests for support of individual sentences should be filed as enhancement tickets.
  • Add sentence synchronization. Currently, there is little or no buffering, which prevents the driver from using multiple types of sentences to generate one cycle of topic outputs.

Nodes

nmea_topic_driver.py

NMEA GPS Topic driver node. Reads NMEA sentences from a ROS topic instead of directly from e.g. a serial port.

Subscribed Topics

nmea_sentence (nmea_gps_driver/NMEASentence)
  • NMEA sentences, 1 per message. The header.stamp should correspond to the time that the message was read from the device for accurate time_reference output. These sentences do not have to be checksummed or otherwise validated before reaching the driver.

Published Topics

fix (sensor_msgs/NavSatFix)
  • GPS position fix reported by the device.
vel (geometry_msgs/TwistStamped)
  • Velocity output from the GPS device. Only published when the device outputs velocity information. The driver does not calculate the velocity based on only position fixes.
time_reference (sensor_msgs/TimeReference)
  • The timestamp from the GPS device is used as the time_ref.

Parameters

~frame_id (string, default: gps) ~time_ref_source (string, default: <the value of ~frame_id>) ~useRMC (bool, default: False)
  • Whether to generate position fixes from GGA sentences or RMC sentences. If True, fixes will be generated from RMC. If False, fixes will be generated based on the GGA sentences. Using GGA sentences allows for covariance output while RMC provides velocity information.

nmea_serial_driver.py

NMEA GPS Serial driver node. Replaces nmea_gps_driver.py to reduce naming conflicts and use new common parsing+driver backend.

Published Topics

fix (sensor_msgs/NavSatFix)
  • GPS position fix reported by the device.
vel (geometry_msgs/TwistStamped)
  • Velocity output from the GPS device. Only published when the device outputs velocity information. The driver does not calculate the velocity based on only position fixes.
time_reference (sensor_msgs/TimeReference)
  • The timestamp from the GPS device is used as the time_ref.

Parameters

~port (string, default: /dev/ttyUSB0)
  • The device path
~baud (int, default: 4800)
  • The baud rate to receive NMEA data.
~frame_id (string, default: gps) ~time_ref_source (string, default: <the value of ~frame_id>) ~useRMC (bool, default: False)
  • Whether to generate position fixes from GGA sentences or RMC sentences. If True, fixes will be generated from RMC. If False, fixes will be generated based on the GGA sentences. Using GGA sentences allows for covariance output while RMC provides velocity information.

nmea_topic_serial_reader.py

Reads NMEA sentences from the specified serial port and publishes them to a ROS topic. This is a simple front-end for use with nmea_topic_driver.py

Published Topics

nmea_sentence (nmea_gps_driver/NMEASentence)
  • A single time-stamped NMEA sentence captured from the serial device

Parameters

~port (string, default: /dev/ttyUSB0)
  • The device path
~baud (int, default: 4800)
  • The baud rate to receive NMEA data.

nmea_gps_driver.py

NMEA GPS Driver node. Deprecated in Hydro in favor of nmea_serial_driver.py to help avoid Python module import conflicts.

Published Topics

fix (sensor_msgs/NavSatFix)
  • GPS position fix reported by the device.
vel (geometry_msgs/TwistStamped)
  • Velocity output from the GPS device. Only published when the device outputs velocity information. The driver does not calculate the velocity based on only position fixes.
time_reference (sensor_msgs/TimeReference)
  • The timestamp from the GPS device is used as the time_ref.

Parameters

~port (string, default: /dev/ttyUSB0)
  • The device path
~baud (int, default: 4800)
  • The baud rate to receive NMEA data.
~frame_id (string, default: gps) ~time_ref_source (string, default: <the value of ~frame_id>) ~useRMC (bool, default: False)
  • Whether to generate position fixes from GGA sentences or a combination of RMC and GSA. If True, fixes will be generated from RMC and GSA. If False, fixes will be generated based on the GGA sentences. Using GGA sentences allows for covariance output while RMC+GSA provides velocity information.

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: nmea_gps_driver/Reviews/Proposed_Hydro_Docs (last edited 2013-05-16 03:35:08 by EricPerko)