mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter: fix optflow position_ok check
We should accept predicted relative horizontal position only when disarmed
This commit is contained in:
parent
21f873662c
commit
be603da579
@ -353,7 +353,13 @@ bool Copter::optflow_position_ok()
|
|||||||
|
|
||||||
// get filter status from EKF
|
// get filter status from EKF
|
||||||
nav_filter_status filt_status = inertial_nav.get_filter_status();
|
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
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user