mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: ensure the dshot type gets set
Same fix as https://github.com/ArduPilot/ardupilot/pull/27093 .
This commit is contained in:
parent
69c76a96d3
commit
43bc80ab59
|
@ -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());
|
||||
|
||||
|
|
Loading…
Reference in New Issue