mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: fix SBP supported status
This commit is contained in:
parent
d3d6099540
commit
512bd08326
@ -282,10 +282,10 @@ AP_GPS_SBP::_attempt_state_update()
|
||||
|
||||
if (pos_llh->flags == 0)
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D;
|
||||
else if (pos_llh->flags == 2)
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
|
||||
else if (pos_llh->flags == 1)
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
|
||||
else if (pos_llh->flags == 2)
|
||||
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
|
||||
|
||||
|
||||
last_full_update_tow = last_vel_ned.tow;
|
||||
|
@ -29,7 +29,7 @@ class AP_GPS_SBP : public AP_GPS_Backend
|
||||
public:
|
||||
AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
||||
|
||||
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT; }
|
||||
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
|
||||
|
||||
// Methods
|
||||
bool read();
|
||||
|
Loading…
Reference in New Issue
Block a user