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.
This commit is contained in:
Randy Mackay 2016-03-22 16:21:58 +09:00
parent 9f9e3843e0
commit a8bea0af03

View File

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