Browse Source

AP_Motors: make sure ESC type is initialized early

apm_2208
Andy Piper 3 years ago committed by Andrew Tridgell
parent
commit
3d9639181e
  1. 1
      libraries/AP_Motors/AP_Motors_Class.cpp

1
libraries/AP_Motors/AP_Motors_Class.cpp

@ -125,6 +125,7 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) @@ -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:

Loading…
Cancel
Save