mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Make magnetometer data available status global
This assists with debugging and makes it consistent with other measurements that are buffered
This commit is contained in:
parent
04228e0b3b
commit
d820a538d5
|
@ -139,16 +139,16 @@ void NavEKF2_core::SelectMagFusion()
|
|||
}
|
||||
|
||||
// check for availability of magnetometer data to fuse
|
||||
bool newMagDataAvailable = RecallMag();
|
||||
magDataToFuse = RecallMag();
|
||||
|
||||
if (newMagDataAvailable) {
|
||||
if (magDataToFuse) {
|
||||
// Control reset of yaw and magnetic field states
|
||||
controlMagYawReset();
|
||||
}
|
||||
|
||||
// determine if conditions are right to start a new fusion cycle
|
||||
// wait until the EKF time horizon catches up with the measurement
|
||||
bool dataReady = (newMagDataAvailable && statesInitialised && use_compass() && yawAlignComplete);
|
||||
bool dataReady = (magDataToFuse && statesInitialised && use_compass() && yawAlignComplete);
|
||||
if (dataReady) {
|
||||
// If we haven't performed the first airborne magnetic field update or have inhibited magnetic field learning, then we use the simple method of declination to maintain heading
|
||||
if(inhibitMagStates) {
|
||||
|
|
|
@ -864,6 +864,7 @@ private:
|
|||
bool rangeDataToFuse; // true when valid range finder height data has arrived at the fusion time horizon.
|
||||
bool baroDataToFuse; // true when valid baro height finder data has arrived at the fusion time horizon.
|
||||
bool gpsDataToFuse; // true when valid GPS data has arrived at the fusion time horizon.
|
||||
bool magDataToFuse; // true when valid magnetometer data has arrived at the fusion time horizon
|
||||
Vector2f heldVelNE; // velocity held when no aiding is available
|
||||
enum AidingMode {AID_ABSOLUTE=0, // GPS aiding is being used (optical flow may also be used) so position estimates are absolute.
|
||||
AID_NONE=1, // no aiding is being used so only attitude and height estimates are available. Either constVelMode or constPosMode must be used to constrain tilt drift.
|
||||
|
|
Loading…
Reference in New Issue