Copter: fix disable ESC calibration for brushed motors

This commit is contained in:
Randy Mackay 2017-11-27 13:03:29 +09:00
parent 650a0e06bd
commit 020e0bfd40

View File

@ -18,7 +18,7 @@ enum ESCCalibrationModes {
// check if we should enter esc calibration mode
void Copter::esc_calibration_startup_check()
{
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED16kHz) {
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED) {
// ESC cal not valid for brushed motors
return;
}