mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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
|
// 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
|
||||||
|
Loading…
Reference in New Issue
Block a user