mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF: Add takeoff and touchdown expected to reported filter status
This commit is contained in:
parent
8c92524b8a
commit
13616d6436
@ -4731,6 +4731,8 @@ void NavEKF::getFilterStatus(nav_filter_status &status) const
|
||||
status.flags.pred_horiz_pos_rel = (optFlowNavPossible || gpsNavPossible) && filterHealthy; // we should be able to estimate a relative position when we enter flight mode
|
||||
status.flags.pred_horiz_pos_abs = gpsNavPossible && filterHealthy; // we should be able to estimate an absolute position when we enter flight mode
|
||||
status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected
|
||||
status.flags.takeoff = takeoffExpected; // The EKF has been told to expect takeoff and is in a ground effect mitigation mode
|
||||
status.flags.touchdown = touchdownExpected; // The EKF has been told to detect touchdown and is in a ground effect mitigation mode
|
||||
}
|
||||
|
||||
// send an EKF_STATUS message to GCS
|
||||
|
@ -32,6 +32,8 @@ union nav_filter_status {
|
||||
uint16_t pred_horiz_pos_rel : 1; // 8 - true if filter expects it can produce a good relative horizontal position estimate - used before takeoff
|
||||
uint16_t pred_horiz_pos_abs : 1; // 9 - true if filter expects it can produce a good absolute horizontal position estimate - used before takeoff
|
||||
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
|
||||
} flags;
|
||||
uint16_t value;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user