Copter: reject changing to throw mode while armed

This commit is contained in:
Randy Mackay 2015-12-19 14:59:44 +09:00
parent 20b6688e77
commit 959c0eccfd
1 changed files with 6 additions and 0 deletions

View File

@ -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;