mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_NavEKF: Update solution status reporting
This patch makes the reporting of an absolute position solution less abbiguaous and ensures that relative position is always true if absolute position is true
This commit is contained in:
parent
ee75f26edb
commit
b21f9daa90
@ -4562,8 +4562,8 @@ void NavEKF::getFilterStatus(uint8_t &status) const
|
||||
status = (!state.quat.is_nan()<<0 | // we can implement a better way to detect invalid attitude, but it is tricky to do reliably
|
||||
!(velTimeout && tasTimeout)<<1 |
|
||||
!((velTimeout && hgtTimeout) || (hgtTimeout && _fusionModeGPS > 0))<<2 |
|
||||
((gpsInhibitMode == 2 && flowDataValid) || (!tasTimeout && assume_zero_sideslip()))<<3 |
|
||||
!(posTimeout || gpsInhibitMode == 1)<<4 |
|
||||
((gpsInhibitMode == 2 && flowDataValid) || (!tasTimeout && assume_zero_sideslip()) || (!posTimeout && gpsInhibitMode == 0))<<3 |
|
||||
(!posTimeout && gpsInhibitMode == 0)<<4 |
|
||||
!hgtTimeout<<5 |
|
||||
!inhibitGndState<<6 |
|
||||
posHoldMode<<7);
|
||||
|
Loading…
Reference in New Issue
Block a user