clearpath_sensors/GPSFix Message

File: clearpath_sensors/GPSFix.msg

# A more complete GPS fix to supplement sensor_msgs/NavSatFix.
Header header

GPSStatus status

# Latitude (degrees). Positive is north of equator; negative is south.
float64 latitude

# Longitude (degrees). Positive is east of prime meridian, negative west.
float64 longitude

# Altitude (meters). Positive is above reference (e.g., sea level).
float64 altitude

# Direction (degrees from north)
float64 track

# Ground speed (meters/second)
float64 speed

# Vertical speed (meters/second)
float64 climb

# Device orientation (units in degrees)
float64 pitch
float64 roll
float64 dip

# GPS time
float64 time

## Dilution of precision; Xdop<=0 means the value is unknown

# Total (positional-temporal) dilution of precision
float64 gdop

# Positional (3D) dilution of precision
float64 pdop

# Horizontal dilution of precision
float64 hdop

# Vertical dilution of precision
float64 vdop

# Temporal dilution of precision
float64 tdop

## Uncertainty of measurement, 95% confidence

# Spherical position uncertainty (meters) [epe]
float64 err

# Horizontal position uncertainty (meters) [eph]
float64 err_horz

# Vertical position uncertainty (meters) [epv]
float64 err_vert

# Track uncertainty (degrees) [epd]
float64 err_track

# Ground speed uncertainty (meters/second) [eps]
float64 err_speed

# Vertical speed uncertainty (meters/second) [epc]
float64 err_climb

# Temporal uncertainty [ept]
float64 err_time

# Orientation uncertainty (degrees)
float64 err_pitch
float64 err_roll
float64 err_dip

# Position covariance [m^2] defined relative to a tangential plane
# through the reported position. The components are East, North, and
# Up (ENU), in row-major order.

float64[9] position_covariance

uint8 COVARIANCE_TYPE_UNKNOWN = 0
uint8 COVARIANCE_TYPE_APPROXIMATED = 1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2
uint8 COVARIANCE_TYPE_KNOWN = 3

uint8 position_covariance_type


Expanded Definition

uint8 COVARIANCE_TYPE_UNKNOWN=0
uint8 COVARIANCE_TYPE_APPROXIMATED=1
uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN=2
uint8 COVARIANCE_TYPE_KNOWN=3
Header header
    uint32 seq
    time stamp
    string frame_id
GPSStatus status
    int16 STATUS_NO_FIX=-1
    int16 STATUS_FIX=0
    int16 STATUS_SBAS_FIX=1
    int16 STATUS_GBAS_FIX=2
    int16 STATUS_DGPS_FIX=18
    int16 STATUS_WAAS_FIX=33
    uint16 SOURCE_NONE=0
    uint16 SOURCE_GPS=1
    uint16 SOURCE_POINTS=2
    uint16 SOURCE_DOPPLER=4
    uint16 SOURCE_ALTIMETER=8
    uint16 SOURCE_MAGNETIC=16
    uint16 SOURCE_GYRO=32
    uint16 SOURCE_ACCEL=64
    Header header
        uint32 seq
        time stamp
        string frame_id
    uint16 satellites_used
    int32[] satellite_used_prn
    uint16 satellites_visible
    int32[] satellite_visible_prn
    int32[] satellite_visible_z
    int32[] satellite_visible_azimuth
    int32[] satellite_visible_snr
    int16 status
    uint16 motion_source
    uint16 orientation_source
    uint16 position_source
float64 latitude
float64 longitude
float64 altitude
float64 track
float64 speed
float64 climb
float64 pitch
float64 roll
float64 dip
float64 time
float64 gdop
float64 pdop
float64 hdop
float64 vdop
float64 tdop
float64 err
float64 err_horz
float64 err_vert
float64 err_track
float64 err_speed
float64 err_climb
float64 err_time
float64 err_pitch
float64 err_roll
float64 err_dip
float64[9] position_covariance
uint8 position_covariance_type