mirror of https://github.com/ArduPilot/ardupilot
Rover: move check for ARMING_CHECK_NONE back into Rover
Rover allows all prearm and arm checks to be bypassed with ARMING_CHECK_NONE. Not all vehicles allow this, so move this bypass back into Rover.
This commit is contained in:
parent
e340873d88
commit
def3bb374f
|
@ -81,6 +81,10 @@ 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)
|
||||||
{
|
{
|
||||||
|
//are arming checks disabled?
|
||||||
|
if (checks_to_perform == ARMING_CHECK_NONE) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
if (SRV_Channels::get_emergency_stop()) {
|
if (SRV_Channels::get_emergency_stop()) {
|
||||||
check_failed(ARMING_CHECK_NONE, report, "Motors Emergency Stopped");
|
check_failed(ARMING_CHECK_NONE, report, "Motors Emergency Stopped");
|
||||||
return false;
|
return false;
|
||||||
|
@ -92,6 +96,15 @@ bool AP_Arming_Rover::pre_arm_checks(bool report)
|
||||||
& proximity_check(report));
|
& proximity_check(report));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
||||||
|
{
|
||||||
|
//are arming checks disabled?
|
||||||
|
if (checks_to_perform == ARMING_CHECK_NONE) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return AP_Arming::arm_checks(method);
|
||||||
|
}
|
||||||
|
|
||||||
// check nothing is too close to vehicle
|
// check nothing is too close to vehicle
|
||||||
bool AP_Arming_Rover::proximity_check(bool report)
|
bool AP_Arming_Rover::proximity_check(bool report)
|
||||||
{
|
{
|
||||||
|
|
|
@ -17,6 +17,7 @@ public:
|
||||||
AP_Arming_Rover &operator=(const AP_Arming_Rover&) = delete;
|
AP_Arming_Rover &operator=(const AP_Arming_Rover&) = delete;
|
||||||
|
|
||||||
bool pre_arm_checks(bool report) override;
|
bool pre_arm_checks(bool report) override;
|
||||||
|
bool arm_checks(AP_Arming::Method method) override;
|
||||||
bool pre_arm_rc_checks(const bool display_failure);
|
bool pre_arm_rc_checks(const bool display_failure);
|
||||||
bool gps_checks(bool display_failure) override;
|
bool gps_checks(bool display_failure) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue