Browse Source

Copter: allow switching to throw without position estimate

The vehicle arming check will still stop the user from arming in throw mode without a good position estimate.
master
Randy Mackay 9 years ago
parent
commit
a8bea0af03
  1. 6
      ArduCopter/control_throw.cpp

6
ArduCopter/control_throw.cpp

@ -17,11 +17,7 @@ bool Copter::throw_init(bool ignore_checks) @@ -17,11 +17,7 @@ bool Copter::throw_init(bool ignore_checks)
}
// this mode needs a position reference
if (position_ok()) {
return true;
} else {
return false;
}
return true;
}
// clean up when exiting throw mode

Loading…
Cancel
Save