diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 9ad1b355ea..75a7d26cec 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -9,7 +9,7 @@ // brake_init - initialise brake controller bool Copter::brake_init(bool ignore_checks) { - if (position_ok() || optflow_position_ok() || ignore_checks) { + if (position_ok() || ignore_checks) { // set desired acceleration to zero wp_nav.clear_pilot_desired_acceleration(); diff --git a/ArduCopter/control_loiter.cpp b/ArduCopter/control_loiter.cpp index d39768744f..425e8dad8c 100644 --- a/ArduCopter/control_loiter.cpp +++ b/ArduCopter/control_loiter.cpp @@ -9,7 +9,7 @@ // loiter_init - initialise loiter controller bool Copter::loiter_init(bool ignore_checks) { - if (position_ok() || optflow_position_ok() || ignore_checks) { + if (position_ok() || ignore_checks) { // set target to current position wp_nav.init_loiter_target(); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index e2e43b7115..9ce5d6cc5e 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -329,7 +329,7 @@ bool Copter::position_ok() } // check ekf position estimate - return ekf_position_ok(); + return (ekf_position_ok() || optflow_position_ok()); } // ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set