Browse Source

AP_NavEKF3: Handle repeated FW flight without magnetometer

The EKF can build up large yaw errors on ground so it is safer to stop using GPS and re-align after launch as per first launch.
c415-sdk
Paul Riseborough 5 years ago committed by Peter Barker
parent
commit
354b551ef0
  1. 9
      libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
  2. 22
      libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp
  3. 1
      libraries/AP_NavEKF3/AP_NavEKF3_core.h

9
libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

@ -283,6 +283,15 @@ void NavEKF3_core::setAidingMode() @@ -283,6 +283,15 @@ void NavEKF3_core::setAidingMode()
(imuSampleTime_ms - lastPosPassTime_ms > maxLossTime_ms);
}
// This is a special case for when we are a fixed wing aircraft vehicle that has landed and
// has no yaw measurement that works when static. Declare the yaw as unaligned (unknown)
// and declare attitude aiding loss so that we fall back into a non-aiding mode
if (assume_zero_sideslip() && onGround && (effectiveMagCal == MagCal::GSF_YAW) && !use_compass()){
yawAlignComplete = false;
finalInflightYawInit = false;
attAidLossCritical = true;
}
if (attAidLossCritical) {
// if the loss of attitude data is critical, then put the filter into a constant position mode
PV_AidingMode = AID_NONE;

22
libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp

@ -343,24 +343,18 @@ void NavEKF3_core::detectFlight() @@ -343,24 +343,18 @@ void NavEKF3_core::detectFlight()
largeHgtChange = true;
}
// Determine to a high certainty we are flying
if (motorsArmed && highGndSpd && (highAirSpd || largeHgtChange)) {
onGround = false;
inFlight = true;
}
// if is possible we are in flight, set the time this condition was last detected
if (motorsArmed && (highGndSpd || highAirSpd || largeHgtChange)) {
airborneDetectTime_ms = imuSampleTime_ms;
if (motorsArmed) {
onGround = false;
}
// Determine to a high certainty we are not flying
// after 5 seconds of not detecting a possible flight condition or we are disarmed, we transition to on-ground mode
if(!motorsArmed || ((imuSampleTime_ms - airborneDetectTime_ms) > 5000)) {
if (highGndSpd && (highAirSpd || largeHgtChange)) {
// to a high certainty we are flying
inFlight = true;
}
} else {
// to a high certainty we are not flying
onGround = true;
inFlight = false;
}
} else {
// Non fly forward vehicle, so can only use height and motor arm status

1
libraries/AP_NavEKF3/AP_NavEKF3_core.h

@ -1008,7 +1008,6 @@ private: @@ -1008,7 +1008,6 @@ private:
bool inFlight; // true when the vehicle is definitely flying
bool prevInFlight; // value inFlight from previous frame - used to detect transition
bool manoeuvring; // boolean true when the flight vehicle is performing horizontal changes in velocity
uint32_t airborneDetectTime_ms; // last time flight movement was detected
Vector6 innovVelPos; // innovation output for a group of measurements
Vector6 varInnovVelPos; // innovation variance output for a group of measurements
Vector6 velPosObs; // observations for combined velocity and positon group of measurements (3x1 m , 3x1 m/s)

Loading…
Cancel
Save