mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Rover: disallow arming in RTL and S_RTL mode
This commit is contained in:
parent
999061704e
commit
961eeb3b58
@ -86,7 +86,8 @@ bool AP_Arming_Rover::pre_arm_checks(bool report)
|
|||||||
& rover.g2.motors.pre_arm_check(report)
|
& rover.g2.motors.pre_arm_check(report)
|
||||||
& fence_checks(report)
|
& fence_checks(report)
|
||||||
& oa_check(report)
|
& oa_check(report)
|
||||||
& parameter_checks(report));
|
& parameter_checks(report)
|
||||||
|
& mode_checks(report));
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
||||||
@ -185,3 +186,13 @@ bool AP_Arming_Rover::parameter_checks(bool report)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check if arming allowed from this mode
|
||||||
|
bool AP_Arming_Rover::mode_checks(bool report)
|
||||||
|
{
|
||||||
|
//display failure if arming in this mode is not allowed
|
||||||
|
if (!rover.control_mode->allows_arming()) {
|
||||||
|
check_failed(report, "Mode not armable");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
@ -30,5 +30,6 @@ protected:
|
|||||||
// the following check functions do not call into AP_Arming
|
// the following check functions do not call into AP_Arming
|
||||||
bool oa_check(bool report);
|
bool oa_check(bool report);
|
||||||
bool parameter_checks(bool report);
|
bool parameter_checks(bool report);
|
||||||
|
bool mode_checks(bool report);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user