Browse Source

Copter: reject changing to throw mode while armed

master
Randy Mackay 9 years ago
parent
commit
959c0eccfd
  1. 6
      ArduCopter/control_throw.cpp

6
ArduCopter/control_throw.cpp

@ -10,6 +10,12 @@ bool Copter::throw_init(bool ignore_checks) @@ -10,6 +10,12 @@ bool Copter::throw_init(bool ignore_checks)
// do not allow helis to use throw to start
return false;
#endif
// do not enter the mode when already armed
if (motors.armed()) {
return false;
}
// this mode needs a position reference
if (position_ok()) {
return true;

Loading…
Cancel
Save