Plane: ensure the dshot type gets set

This commit is contained in:
Andy Piper 2024-05-18 14:10:48 +01:00 committed by Randy Mackay
parent cf5d3ba530
commit e59862a739

View File

@ -135,6 +135,7 @@ void Plane::init_ardupilot()
if (g2.oneshot_mask != 0) { if (g2.oneshot_mask != 0) {
hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
} }
hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type());
set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED);