mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: use RC_CALIB_MIN_LIMIT_PWM and RC_CALIB_MAX_LIMIT_PWM
This commit is contained in:
parent
9dcaf155a6
commit
c0348b034f
@ -19,11 +19,11 @@ bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure)
|
||||
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);
|
||||
return 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);
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user