From 1ffe75957ed0a0b0f9f83505d6731f40658d1894 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 15 Mar 2018 21:24:22 +1100 Subject: [PATCH] Copter: fixed ESC calibration for DShot --- ArduCopter/esc_calibration.cpp | 2 +- ArduCopter/system.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 5dd9767024..1d16e29aac 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -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; } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 8fbb2b613c..d243e5fb6b 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -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); }