@ -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_BRUSHED) {
if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) {
// ESC cal not valid for brushed motors
return;
}
@ -638,7 +638,7 @@ void Copter::allocate_motors(void)
// brushed 16kHz defaults to 16kHz pulses
g.rc_speed.set_default(16000);