File: sensor_msgs/NavSatStatus.msg
Raw Message Definition
# Navigation Satellite fix status for any Global Navigation Satellite System
# Whether to output an augmented fix is determined by both the fix
# type and the last time differential corrections were received. A
# fix is valid when status >= STATUS_FIX.
int8 STATUS_NO_FIX = -1 # unable to fix position
int8 STATUS_FIX = 0 # unaugmented fix
int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation
int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation
int8 status
# Bits defining which Global Navigation Satellite System signals were
# used by the receiver.
uint16 SERVICE_GPS = 1
uint16 SERVICE_GLONASS = 2
uint16 SERVICE_COMPASS = 4 # includes BeiDou.
uint16 SERVICE_GALILEO = 8
uint16 service
Compact Message Definition
int8 STATUS_NO_FIX=-1
int8 STATUS_FIX=0
int8 STATUS_SBAS_FIX=1
int8 STATUS_GBAS_FIX=2
uint16 SERVICE_GPS=1
uint16 SERVICE_GLONASS=2
uint16 SERVICE_COMPASS=4
uint16 SERVICE_GALILEO=8
int8 status
uint16 service