mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: return true straight away in prearm checks if armed
mirrors equivalent clause in Plane
This commit is contained in:
parent
9b1b06fd95
commit
082eb83f30
@ -71,6 +71,11 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
|
|||||||
|
|
||||||
bool AP_Arming_Rover::pre_arm_checks(bool report)
|
bool AP_Arming_Rover::pre_arm_checks(bool report)
|
||||||
{
|
{
|
||||||
|
if (armed) {
|
||||||
|
// if we are already armed then skip the checks
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
//are arming checks disabled?
|
//are arming checks disabled?
|
||||||
if (checks_to_perform == 0) {
|
if (checks_to_perform == 0) {
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user