mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
Copter: fixed ESC calibration for DShot
This commit is contained in:
parent
26d279e165
commit
1ffe75957e
@ -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
|
||||
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…
Reference in New Issue
Block a user