From be603da5793a70414ecf33e95ef42b3b55d6de5d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 27 Aug 2015 20:54:09 +0900 Subject: [PATCH] Copter: fix optflow position_ok check We should accept predicted relative horizontal position only when disarmed --- ArduCopter/system.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index a325ad98de..e1fd038efa 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -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 }