mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: use RC_CALIB_MIN_LIMIT_PWM and RC_CALIB_MAX_LIMIT_PWM
This commit is contained in:
parent
c0348b034f
commit
68a27e3b41
|
@ -1260,11 +1260,11 @@ 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 (channel->get_radio_min() > 1300) {
|
||||
if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
|
||||
ret = false;
|
||||
}
|
||||
if (channel->get_radio_max() < 1700) {
|
||||
if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {
|
||||
check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
|
||||
ret = false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue