mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: factor out an rc_throttle_failsafe_checks method
NFC, preparing to call this from elsewhere
This commit is contained in:
parent
46dacd3b61
commit
1e3f37908c
@ -63,6 +63,34 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
|
||||
& AP_Arming::pre_arm_checks(display_failure);
|
||||
}
|
||||
|
||||
bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const
|
||||
{
|
||||
// throttle failsafe. In this case the parameter also gates the
|
||||
// no-pulses RC failure case - the radio-in value can be zero due
|
||||
// to not having received any RC pulses at all. Note that if we
|
||||
// have ever seen RC and then we *lose* RC then these checks are
|
||||
// likely to pass if the user is relying on no-pulses to detect RC
|
||||
// failure. However, arming is precluded in that case by being in
|
||||
// RC failsafe.
|
||||
if (copter.g.failsafe_throttle == FS_THR_DISABLED) {
|
||||
return true;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
const char *rc_item = "Collective";
|
||||
#else
|
||||
const char *rc_item = "Throttle";
|
||||
#endif
|
||||
|
||||
// check throttle is not too low - must be above failsafe throttle
|
||||
if (copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
|
||||
check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item);
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_Arming_Copter::barometer_checks(bool display_failure)
|
||||
{
|
||||
if (!AP_Arming::barometer_checks(display_failure)) {
|
||||
@ -597,17 +625,15 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
||||
|
||||
// check throttle
|
||||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) {
|
||||
if (!rc_throttle_failsafe_checks(true)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
const char *rc_item = "Collective";
|
||||
#else
|
||||
const char *rc_item = "Throttle";
|
||||
#endif
|
||||
// check throttle is not too low - must be above failsafe throttle
|
||||
if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
|
||||
check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item);
|
||||
return false;
|
||||
}
|
||||
|
||||
// check throttle is not too high - skips checks if arming from GCS in Guided
|
||||
if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS))) {
|
||||
// above top of deadband is too always high
|
||||
|
@ -48,6 +48,7 @@ protected:
|
||||
bool gcs_failsafe_check(bool display_failure);
|
||||
bool winch_checks(bool display_failure) const;
|
||||
bool alt_checks(bool display_failure);
|
||||
bool rc_throttle_failsafe_checks(bool display_failure) const;
|
||||
|
||||
void set_pre_arm_check(bool b);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user