ErbMessageID
The available ERB Message IDs.
@ ERB_MessageId_RTK
RTK information.
@ ERB_MessageId_POS
Geodetic position solution.
@ ERB_MessageId_NONE
No Message Class specified.
@ ERB_MessageId_VEL
Velocity solution in NED.
@ ERB_MessageId_STAT
Receiver navigation status.
@ ERB_MessageId_VER
Version of protocol.
@ ERB_MessageId_SVI
Space vehicle information.
@ ERB_MessageId_DPOS
Dilution of precision.
ErbMessageID getMsgIdFromString(const std::string &idName)
Get the ERB Msg ID From String object.
ErrorDetectionMode
Error detection modes available.
@ ERRORDETECTIONMODE_CHECKSUM
16-bit checksum is used
@ ERRORDETECTIONMODE_NONE
No error detection is used.
Dilution of Precision This message outputs dimensionless values of DOP. These values are scaled by fa...
uint16_t dopVer
Vertical DOP [*0.01].
uint16_t dopPos
Position DOP [*0.01].
uint16_t dopHor
Horizontal DOP [*0.01].
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
uint16_t dopGeo
Geometric DOP [*0.01].
Geodetic Position Solution.
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
double height
Height above ellipsoid [m].
uint32_t vAcc
Vertical accuracy estimate [mm].
double lat
Latitude [deg].
double lon
Longitude [deg].
uint32_t hAcc
Horizontal accuracy estimate [mm].
double hMSL
Height above mean sea level [m].
RTK Information This message output information about RTK.
int32_t baselineN
Distance between base and rover along the north axis [mm].
uint16_t age
Age of differential [s/// 1e-2] (0 when no corrections, 0xFFFF indicates overflow)
uint16_t arRatio
AR Ratio [*1e-1].
int32_t baselineD
Distance between base and rover along the down axis [mm].
uint16_t weekGPS
GPS Week Number of last baseline [weeks].
int32_t baselineE
Distance between base and rover along the east axis [mm].
uint32_t timeGPS
GPS Time of Week of last baseline [ms].
uint8_t numSV
Number of satellites used for RTK calculation.
Receiver Navigation Status This message contains status of Fix, its type and also the number of used ...
uint8_t numSV
Number of used SVs.
uint16_t weekGPS
GPS week number of the navigation epoch [weeks].
uint8_t fixType
GPSfix type: 0x00 - no Fix, 0x01 - Single, 0x02 - Float, 0x03 - RTK Fix.
uint8_t fixStatus
Navigation Fix Status. If position and velocity are valid 0x01, else 0x00.
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
Space Vehicle Information This message output information about observation satellites.
int32_t carPh
Carrier phase [cycle/// 1e-2].
uint16_t azim
Azimuth in degrees [deg/// 1e-1].
int32_t psRan
Pseudo range residual [m].
int32_t freqD
Doppler frequency [Hz/// 1e-3].
uint8_t typeSV
GNSS identifier 0-GPS, 1-GLONASS, 2-Galileo, 3-QZSS, 4-Beidou, 5-LEO, 6-SBAS.
uint8_t nSV
Number of Satellites.
uint8_t idSV
Satellite identifier (see Satellite Numbering)
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
uint16_t snr
Signal strength [dBhz/// 0.25].
uint16_t elev
Elevation in degrees [deg/// 1e-1].
Velocity Solution in NED See important comments concerning validity of position given in section Navi...
int32_t velN
North velocity component [cm/s].
int32_t heading
Heading of motion 2-D [deg/// 1e-5].
uint32_t sAcc
Speed accuracy Estimation [cm/s].
int32_t velD
Down velocity component [cm/s].
uint32_t gSpeed
Ground speed (2-D)
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
uint32_t speed
Speed (3-D)
int32_t velE
East velocity component [cm/s].
uint8_t verL
Low level of version.
uint8_t verM
Medium level of version.
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
uint8_t verH
High level of version.