mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover : add pilot_throttle_checks() to check throttle failsafe
This adds pilot_throttle_checks to check for throttle failsafe and prevents arming if throttle failsafe is triggered
This commit is contained in:
parent
50f9d2601f
commit
1b8fc31fcd
@ -89,7 +89,8 @@ bool AP_Arming_Rover::pre_arm_checks(bool report)
|
|||||||
& motor_checks(report)
|
& motor_checks(report)
|
||||||
& oa_check(report)
|
& oa_check(report)
|
||||||
& parameter_checks(report)
|
& parameter_checks(report)
|
||||||
& mode_checks(report));
|
& mode_checks(report)
|
||||||
|
& pilot_throttle_checks(report));
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
|
||||||
@ -188,6 +189,19 @@ bool AP_Arming_Rover::parameter_checks(bool report)
|
|||||||
return true;
|
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
|
// check if arming allowed from this mode
|
||||||
bool AP_Arming_Rover::mode_checks(bool report)
|
bool AP_Arming_Rover::mode_checks(bool report)
|
||||||
{
|
{
|
||||||
|
@ -32,5 +32,6 @@ protected:
|
|||||||
bool parameter_checks(bool report);
|
bool parameter_checks(bool report);
|
||||||
bool mode_checks(bool report);
|
bool mode_checks(bool report);
|
||||||
bool motor_checks(bool report);
|
bool motor_checks(bool report);
|
||||||
|
bool pilot_throttle_checks(bool report);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user