Copter: ignore flight mode change requests if we're already in the desired mode

This commit is contained in:
Randy Mackay 2013-10-15 11:53:56 +09:00
parent deb171a869
commit 7c7f235a97
1 changed files with 5 additions and 0 deletions

View File

@ -340,6 +340,11 @@ static bool set_mode(uint8_t mode)
bool success = false;
bool ignore_checks = !motors.armed(); // allow switching to any mode if disarmed. We rely on the arming check to perform
// return immediately if we are already in the desired mode
if (mode == control_mode) {
return true;
}
switch(mode) {
case ACRO:
success = true;