AP_Arming: remove min-max-configured pre-arm checks
This commit is contained in:
parent
2365cdf90a
commit
eaefdcfac2
@ -687,10 +687,6 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe
|
|||||||
const RC_Channel *channel = channels[i];
|
const RC_Channel *channel = channels[i];
|
||||||
const char *channel_name = channel_names[i];
|
const char *channel_name = channel_names[i];
|
||||||
// check if radio has been calibrated
|
// check if radio has been calibrated
|
||||||
if (check_min_max && !channel->min_max_configured()) {
|
|
||||||
check_failed(ARMING_CHECK_RC, display_failure, "RC %s not configured", channel_name);
|
|
||||||
ret = false;
|
|
||||||
}
|
|
||||||
if (channel->get_radio_min() > 1300) {
|
if (channel->get_radio_min() > 1300) {
|
||||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
|
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
|
||||||
ret = false;
|
ret = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user