AP_NavEKF: base EKF decisions on vehicle class
using the vehicle class rather than the build macros allows this to work correctly in replay
This commit is contained in:
parent
92daa15ccc
commit
5514a9f690
@ -321,27 +321,29 @@ bool AP_AHRS_NavEKF::using_EKF(void) const
|
|||||||
if (!ret) {
|
if (!ret) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
|
||||||
nav_filter_status filt_state;
|
if (_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
||||||
EKF.getFilterStatus(filt_state);
|
_vehicle_class == AHRS_VEHICLE_GROUND) {
|
||||||
if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && _gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
nav_filter_status filt_state;
|
||||||
// if the EKF is not fusing GPS and we have a 3D lock, then
|
EKF.getFilterStatus(filt_state);
|
||||||
// plane and rover would prefer to use the GPS position from
|
if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && _gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
// DCM. This is a safety net while some issues with the EKF
|
// if the EKF is not fusing GPS and we have a 3D lock, then
|
||||||
// get sorted out
|
// plane and rover would prefer to use the GPS position from
|
||||||
return false;
|
// DCM. This is a safety net while some issues with the EKF
|
||||||
|
// get sorted out
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!filt_state.flags.attitude ||
|
||||||
|
!filt_state.flags.horiz_vel ||
|
||||||
|
!filt_state.flags.vert_vel ||
|
||||||
|
!filt_state.flags.horiz_pos_abs ||
|
||||||
|
!filt_state.flags.vert_pos) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (!filt_state.flags.attitude ||
|
|
||||||
!filt_state.flags.horiz_vel ||
|
|
||||||
!filt_state.flags.vert_vel ||
|
|
||||||
!filt_state.flags.horiz_pos_abs ||
|
|
||||||
!filt_state.flags.vert_pos) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user