gpsd_client relays GPS readings into ROS from the gpsd program.

This package publishes the device's location using a local copy of the NavSatFix message type that will be introduced to sensor_msgs in ROS Diamondback.

Usage

Before gpsd_client starts, GPSd must be running.

GPSd preparation

Ubuntu

On Ubuntu, GPSd will start automatically. Specify your GPS device's port in the /etc/default/gpsd file. For a device on the second serial port, e.g., set DEVICES="/dev/ttyS1".

If you use any USB-serial devices, you may want to disable GPSd's USB exploration feature by setting the USBAUTO parameter to "false" in /etc/defaults/gpsd. Without that change, GPSd will manipulate the line speeds on your USB-serial ports, potentially causing communication failure.

Other platforms

Depending on your system, you may need to add the GPSd startup script to the current system runlevel or execute GPSd manually.

Running gpsd_client

Specify the host and port number where GPSd can be found, and choose a message family:

$ rosrun gpsd_client gpsd_client _host:=localhost _port:=2947 _report_as:=navsat

Nodes

gpsd_client

gpsd_client relays GPS readings into ROS from the gpsd program.

Published Topics

fix [1] (gps_common/GPSFix)
  • Latitude, longitude, altitude, covariance, time, etc.
status [1] (gps_common/GPSStatus)
  • Status of GPS receiver, including satellite lists.
fix [2] (gps_common/NavSatFix)
  • Latitude, longitude, altitude, covariance and status.

Parameters

~host (string, default: localhost)
  • Sets the host name.
~port (int, default: 2947)
  • Sets the port.
~report_as (string, default: gps)
  • [1] If "gps", publish GPSFix/GPSStatus. [2] If "navsat", publish NavSatFix.

GPS Hardware

The following GPS devices have been tested with gpsd_client and found to work:

  • Garmin 18x LVC (serial connection)

Please refer to gpsd's compatibility list for more receiver models that should work with this driver.

gpsd_client relays GPS readings into ROS from the gpsd program.

This package publishes the device's location using the NavSatFix message type that was introduced to sensor_msgs in ROS Diamondback.

Usage

Before gpsd_client starts, GPSd must be running.

GPSd preparation

Ubuntu

On Ubuntu, GPSd will start automatically. Specify your GPS device's port in the /etc/default/gpsd file. For a device on the second serial port, e.g., set DEVICES="/dev/ttyS1".

If you use any USB-serial devices, you may want to disable GPSd's USB exploration feature by setting the USBAUTO parameter to "false" in /etc/defaults/gpsd. Without that change, GPSd will manipulate the line speeds on your USB-serial ports, potentially causing communication failure.

Other platforms

Depending on your system, you may need to add the GPSd startup script to the current system runlevel or execute GPSd manually.

Running gpsd_client

Specify the host and port number where GPSd can be found:

$ rosrun gpsd_client gpsd_client _host:=localhost _port:=2947

Nodes

gpsd_client

gpsd_client relays GPS readings into ROS from the gpsd program.

Published Topics

fix (sensor_msgs/NavSatFix)
  • Latitude, longitude, altitude, covariance and status.
fix_extended (gps_common/GPSFix)
  • Includes additional GPS-specific data.

Parameters

~host (string, default: localhost)
  • Sets the host name.
~port (int, default: 2947)
  • Sets the port.

GPS Hardware

The following GPS devices have been tested with gpsd_client and found to work:

  • Garmin 18x LVC (serial connection)

Please refer to gpsd's compatibility list for more receiver models that should work with this driver.

Wiki: gpsd_client (last edited 2013-01-16 06:09:16 by Boris)