mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: added using_gps status bit
This commit is contained in:
parent
260e7679dd
commit
6154db5cf8
|
@ -4823,6 +4823,7 @@ void NavEKF::getFilterStatus(nav_filter_status &status) const
|
|||
status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
|
||||
status.flags.takeoff = expectGndEffectTakeoff; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
|
||||
status.flags.touchdown = expectGndEffectTouchdown; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
|
||||
status.flags.using_gps = (imuSampleTime_ms - lastPosPassTime) < 2000;
|
||||
}
|
||||
|
||||
// send an EKF_STATUS message to GCS
|
||||
|
|
|
@ -34,6 +34,7 @@ union nav_filter_status {
|
|||
uint16_t takeoff_detected : 1; // 10 - true if optical flow takeoff has been detected
|
||||
uint16_t takeoff : 1; // 11 - true if filter is compensating for baro errors during takeoff
|
||||
uint16_t touchdown : 1; // 12 - true if filter is compensating for baro errors during touchdown
|
||||
uint16_t using_gps : 1; // 13 - true if we are using GPS position
|
||||
} flags;
|
||||
uint16_t value;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue