mirror of https://github.com/ArduPilot/ardupilot
Copter: reject changing to throw mode while armed
This commit is contained in:
parent
20b6688e77
commit
959c0eccfd
|
@ -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…
Reference in New Issue