mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fixed arming with no compass in plane
allow arming if the GPS quality is good, the yaw alignment and position will fix itself once the vehicle starts moving
This commit is contained in:
parent
ac40a20c02
commit
63d385ffb1
|
@ -1050,8 +1050,7 @@ AP_AHRS_NavEKF::EKF_TYPE AP_AHRS_NavEKF::active_EKF_type(void) const
|
|||
accept EKF as healthy to allow arming. Once we reach
|
||||
speed the EKF should get yaw alignment
|
||||
*/
|
||||
if (filt_state.flags.pred_horiz_pos_abs &&
|
||||
filt_state.flags.pred_horiz_pos_rel) {
|
||||
if (filt_state.flags.gps_quality_good) {
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue