mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Arming: remove redundant trim checks in Copter/Sub
The main rc_calibration_checks method checks all channels, not just the subset being tested explicitly on Copter/Sub.
The code making this redundant was added in 1b18a78d1d
with a comment "Add a RC check that (<=min trim max) for all channels.
This commit is contained in:
parent
686da203f5
commit
575d803904
@ -1689,23 +1689,6 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
|
||||
ret = false;
|
||||
}
|
||||
bool fail = true;
|
||||
if (i == 2) {
|
||||
// skip checking trim for throttle as older code did not check it
|
||||
fail = false;
|
||||
}
|
||||
if (channel->get_radio_trim() < channel->get_radio_min()) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim below min", channel_name);
|
||||
if (fail) {
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
if (channel->get_radio_trim() > channel->get_radio_max()) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim above max", channel_name);
|
||||
if (fail) {
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user