AP_Arming: remove min-max-configured pre-arm checks

This commit is contained in:
Peter Barker 2018-08-04 17:06:04 +10:00 committed by Andrew Tridgell
parent 2365cdf90a
commit eaefdcfac2
1 changed files with 0 additions and 4 deletions

View File

@ -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 char *channel_name = channel_names[i];
// 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) {
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
ret = false;