From 7dcdf7b32535f128b0fcdfaa09ca0d11068ad329 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 23 May 2022 13:59:22 +0100 Subject: [PATCH] AP_Motors: make sure ESC type is initialized early --- libraries/AP_Motors/AP_Motors_Class.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 7f51eea1cc..f8bbf51276 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -124,6 +124,7 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) const uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); hal.rcout->set_freq(mask, freq_hz); + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); switch (pwm_type(_pwm_type.get())) { case PWM_TYPE_ONESHOT: