From fb5986c4ecde67c48fc3156741ed6eddbe86cb06 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 14 Oct 2015 11:52:48 +0900 Subject: [PATCH] Copter: position_ok when optical flow ok Previously the GPS based absolute position was required This allows using optical flow in all flight modes --- ArduCopter/control_brake.cpp | 2 +- ArduCopter/control_loiter.cpp | 2 +- ArduCopter/system.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 424f7f139d..16e734c792 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 5db4de138d..0b2bb6bd46 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 dacc97dc47..003e434fe5 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -317,7 +317,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