AP_AHRS: allow for EKF without GPS on plane in VTOL modes

this allows for testing quadplanes indoors
This commit is contained in:
Andrew Tridgell 2016-03-05 08:52:40 +11:00
parent e6d2617936
commit d0b67ce007
2 changed files with 11 additions and 5 deletions

View File

@ -34,7 +34,7 @@ AP_AHRS_NavEKF::AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gp
AP_AHRS_DCM(ins, baro, gps),
EKF1(_EKF1),
EKF2(_EKF2),
_flags(flags)
_ekf_flags(flags)
{
_dcm_matrix.identity();
}
@ -713,9 +713,15 @@ AP_AHRS_NavEKF::EKF_TYPE AP_AHRS_NavEKF::active_EKF_type(void) const
#endif
}
/*
fixed wing and rover when in fly_forward mode will fall back to
DCM if the EKF doesn't have GPS. This is the safest option as
DCM is very robust
*/
if (ret != EKF_TYPE_NONE &&
(_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
_vehicle_class == AHRS_VEHICLE_GROUND)) {
(_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
_vehicle_class == AHRS_VEHICLE_GROUND) &&
_flags.fly_forward) {
nav_filter_status filt_state;
if (ret == EKF_TYPE1) {
EKF1.getFilterStatus(filt_state);

View File

@ -217,7 +217,7 @@ private:
EKF_TYPE active_EKF_type(void) const;
bool always_use_EKF() const {
return _flags & FLAG_ALWAYS_USE_EKF;
return _ekf_flags & FLAG_ALWAYS_USE_EKF;
}
NavEKF &EKF1;
@ -232,7 +232,7 @@ private:
Vector3f _accel_ef_ekf_blended;
const uint16_t startup_delay_ms = 1000;
uint32_t start_time_ms = 0;
Flags _flags;
Flags _ekf_flags;
uint8_t ekf_type(void) const;
void update_DCM(void);