Skip to content

Commit

Permalink
AP_Periph: ensure the dshot type gets set
Browse files Browse the repository at this point in the history
Same fix as #27093 .
  • Loading branch information
tpwrules authored and peterbarker committed Jul 9, 2024
1 parent 69c76a9 commit 43bc80a
Showing 1 changed file with 4 additions and 0 deletions.
4 changes: 4 additions & 0 deletions Tools/AP_Periph/rc_out.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());

Expand Down

0 comments on commit 43bc80a

Please sign in to comment.