mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: only check trim on valid channel count
This commit is contained in:
parent
6a4dbd0c70
commit
c6ac1bf95a
|
@ -456,11 +456,15 @@ bool AP_Arming::hardware_safety_check(bool report)
|
|||
bool AP_Arming::rc_calibration_checks(bool report)
|
||||
{
|
||||
bool check_passed = true;
|
||||
const uint8_t num_channels = RC_Channels::get_valid_channel_count();
|
||||
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
|
||||
const RC_Channel *ch = RC_Channels::rc_channel(i);
|
||||
if (ch == nullptr) {
|
||||
continue;
|
||||
}
|
||||
if (i >= num_channels && !(ch->has_override())) {
|
||||
continue;
|
||||
}
|
||||
const uint16_t trim = ch->get_radio_trim();
|
||||
if (ch->get_radio_min() > trim) {
|
||||
if (report) {
|
||||
|
|
Loading…
Reference in New Issue