mirror of https://github.com/ArduPilot/ardupilot
Rover: Copter: remove pilot_throttle_checks()
This method is redundant as radio_failsafe_check() takes care of below acceptable value of throttle.
This commit is contained in:
parent
8b526526c2
commit
dbd6cd1a58
|
@ -89,8 +89,7 @@ bool AP_Arming_Rover::pre_arm_checks(bool report)
|
|||
& motor_checks(report)
|
||||
& oa_check(report)
|
||||
& parameter_checks(report)
|
||||
& mode_checks(report)
|
||||
& pilot_throttle_checks(report));
|
||||
& mode_checks(report));
|
||||
}
|
||||
|
||||
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
||||
|
@ -189,19 +188,6 @@ bool AP_Arming_Rover::parameter_checks(bool report)
|
|||
return true;
|
||||
}
|
||||
|
||||
// check throttle is above failsafe throttle
|
||||
bool AP_Arming_Rover::pilot_throttle_checks(bool report)
|
||||
{
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) {
|
||||
if (rover.g.fs_throttle_enabled != FS_THR_DISABLED && rover.channel_throttle->get_radio_in() < rover.g.fs_throttle_value) {
|
||||
check_failed(ARMING_CHECK_RC, report, "Throttle below failsafe");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// check if arming allowed from this mode
|
||||
bool AP_Arming_Rover::mode_checks(bool report)
|
||||
{
|
||||
|
|
|
@ -32,6 +32,5 @@ protected:
|
|||
bool parameter_checks(bool report);
|
||||
bool mode_checks(bool report);
|
||||
bool motor_checks(bool report);
|
||||
bool pilot_throttle_checks(bool report);
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue