Copter: fixed ESC calibration for DShot

This commit is contained in:
Andrew Tridgell 2018-03-15 21:24:22 +11:00
parent 26d279e165
commit 1ffe75957e
2 changed files with 2 additions and 2 deletions

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_BRUSHED) {
if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) {
// ESC cal not valid for brushed motors
return;
}

View File

@ -638,7 +638,7 @@ void Copter::allocate_motors(void)
}
// brushed 16kHz defaults to 16kHz pulses
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED) {
if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) {
g.rc_speed.set_default(16000);
}