Copter: fix disable ESC calibration for brushed motors
This commit is contained in:
parent
650a0e06bd
commit
020e0bfd40
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user