Browse Source

Copter: position_ok when optical flow ok

Previously the GPS based absolute position was required
This allows using optical flow in all flight modes
master
Randy Mackay 10 years ago
parent
commit
9b80ab18ae
  1. 2
      ArduCopter/control_brake.cpp
  2. 2
      ArduCopter/control_loiter.cpp
  3. 2
      ArduCopter/system.cpp

2
ArduCopter/control_brake.cpp

@ -9,7 +9,7 @@ @@ -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();

2
ArduCopter/control_loiter.cpp

@ -9,7 +9,7 @@ @@ -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();

2
ArduCopter/system.cpp

@ -329,7 +329,7 @@ bool Copter::position_ok() @@ -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

Loading…
Cancel
Save