mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: replace VDOP with extra GPS status bits
This removes VDOP (not really that useful) and replaces two of those bits with GPS status info that now allows to differentiate between 3D fix, DGPS, RTK Float, and RTK Fixed. This is written to maximize backwards compatibility (by not shifting any other bits of the gps_status variable)
This commit is contained in:
parent
2c22a17f85
commit
949aa4d9ca
|
@ -633,12 +633,12 @@ uint32_t AP_Frsky_Telem::calc_gps_status(void)
|
|||
|
||||
// number of GPS satellites visible (limit to 15 (0xF) since the value is stored on 4 bits)
|
||||
gps_status = (_ahrs.get_gps().num_sats() < GPS_SATS_LIMIT) ? _ahrs.get_gps().num_sats() : GPS_SATS_LIMIT;
|
||||
// GPS receiver status (limit to 3 (0x3) since the value is stored on 2 bits: NO_GPS = 0, NO_FIX = 1, GPS_OK_FIX_2D = 2, GPS_OK_FIX_3D or GPS_OK_FIX_3D_DGPS or GPS_OK_FIX_3D_RTK = 3)
|
||||
// GPS receiver status (limit to 0-3 (0x3) since the value is stored on 2 bits: NO_GPS = 0, NO_FIX = 1, GPS_OK_FIX_2D = 2, GPS_OK_FIX_3D or GPS_OK_FIX_3D_DGPS or GPS_OK_FIX_3D_RTK_FLOAT or GPS_OK_FIX_3D_RTK_FIXED = 3)
|
||||
gps_status |= ((_ahrs.get_gps().status() < GPS_STATUS_LIMIT) ? _ahrs.get_gps().status() : GPS_STATUS_LIMIT)<<GPS_STATUS_OFFSET;
|
||||
// GPS horizontal dilution of precision in dm
|
||||
gps_status |= prep_number(roundf(_ahrs.get_gps().get_hdop() * 0.1f),2,1)<<GPS_HDOP_OFFSET;
|
||||
// GPS vertical dilution of precision in dm
|
||||
gps_status |= prep_number(roundf(_ahrs.get_gps().get_vdop() * 0.1f),2,1)<<GPS_VDOP_OFFSET;
|
||||
// GPS receiver advanced status (0: no advanced fix, 1: GPS_OK_FIX_3D_DGPS, 2: GPS_OK_FIX_3D_RTK_FLOAT, 3: GPS_OK_FIX_3D_RTK_FIXED)
|
||||
gps_status |= ((_ahrs.get_gps().status() > GPS_STATUS_LIMIT) ? _ahrs.get_gps().status()-GPS_STATUS_LIMIT : 0)<<GPS_ADVSTATUS_OFFSET;
|
||||
// Altitude MSL in dm
|
||||
const Location &loc = _ahrs.get_gps().location();
|
||||
gps_status |= prep_number(roundf(loc.alt * 0.1f),2,2)<<GPS_ALTMSL_OFFSET;
|
||||
|
|
|
@ -76,7 +76,7 @@ for FrSky SPort Passthrough
|
|||
#define GPS_STATUS_LIMIT 0x3
|
||||
#define GPS_STATUS_OFFSET 4
|
||||
#define GPS_HDOP_OFFSET 6
|
||||
#define GPS_VDOP_OFFSET 14
|
||||
#define GPS_ADVSTATUS_OFFSET 14
|
||||
#define GPS_ALTMSL_OFFSET 22
|
||||
// for battery data
|
||||
#define BATT_VOLTAGE_LIMIT 0x1FF
|
||||
|
|
Loading…
Reference in New Issue