diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index 93614c1352..6f8459db37 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -63,6 +63,10 @@ void AP_Periph_FW::rcout_init() // run this once and at 1Hz to configure aux and esc ranges rcout_init_1Hz(); +#if HAL_DSHOT_ENABLED + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); +#endif + // setup ESCs with the desired PWM type, allowing for DShot SRV_Channels::init(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());