AP_Motors: make sure ESC type is initialized early

This commit is contained in:
Andy Piper 2022-05-23 13:59:22 +01:00 committed by Andrew Tridgell
parent e95d116979
commit 3d9639181e
1 changed files with 1 additions and 0 deletions

View File

@ -125,6 +125,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: