mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: integrate pre arm check if regular and skid steering configured
This commit is contained in:
parent
ebe3ec88a7
commit
c17549c7ff
|
@ -69,3 +69,8 @@ bool AP_Arming_Rover::gps_checks(bool display_failure)
|
|||
// call parent gps checks
|
||||
return AP_Arming::gps_checks(display_failure);
|
||||
}
|
||||
|
||||
bool AP_Arming_Rover::pre_arm_checks(bool report)
|
||||
{
|
||||
return rover.g2.motors.pre_arm_check(report) & AP_Arming::pre_arm_checks(report);
|
||||
}
|
||||
|
|
|
@ -18,6 +18,7 @@ public:
|
|||
AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
|
||||
AP_Arming_Rover &operator=(const AP_Baro&) = delete;
|
||||
|
||||
bool pre_arm_checks(bool report) override;
|
||||
bool pre_arm_rc_checks(const bool display_failure);
|
||||
bool gps_checks(bool display_failure) override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue