Browse Source

Copter: fixed ESC calibration for DShot

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
1ffe75957e
  1. 2
      ArduCopter/esc_calibration.cpp
  2. 2
      ArduCopter/system.cpp

2
ArduCopter/esc_calibration.cpp

@ -18,7 +18,7 @@ enum ESCCalibrationModes { @@ -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;
}

2
ArduCopter/system.cpp

@ -638,7 +638,7 @@ void Copter::allocate_motors(void) @@ -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);
}

Loading…
Cancel
Save