From 43bc80ab595717cdecee5a2a971afc5e7df394a8 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Wed, 3 Jul 2024 14:38:16 -0500 Subject: [PATCH] AP_Periph: ensure the dshot type gets set Same fix as https://github.com/ArduPilot/ardupilot/pull/27093 . --- Tools/AP_Periph/rc_out.cpp | 4 ++++ 1 file changed, 4 insertions(+) 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());