mirror of https://github.com/ArduPilot/ardupilot
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:
parent
9f9e3843e0
commit
a8bea0af03
|
@ -17,11 +17,7 @@ bool Copter::throw_init(bool ignore_checks)
|
|||
}
|
||||
|
||||
// this mode needs a position reference
|
||||
if (position_ok()) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// clean up when exiting throw mode
|
||||
|
|
Loading…
Reference in New Issue