Copter: fix optflow position_ok check

We should accept predicted relative horizontal position only when disarmed
This commit is contained in:
Randy Mackay 2015-08-27 20:54:09 +09:00
parent 78ac1340c8
commit a1ac2bff56
1 changed files with 7 additions and 1 deletions

View File

@ -353,7 +353,13 @@ bool Copter::optflow_position_ok()
// get filter status from EKF
nav_filter_status filt_status = inertial_nav.get_filter_status();
return (filt_status.flags.horiz_pos_rel || filt_status.flags.pred_horiz_pos_rel);
// if disarmed we accept a predicted horizontal relative position
if (!motors.armed()) {
return (filt_status.flags.pred_horiz_pos_rel);
} else {
return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode);
}
#endif
}