diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index eb41b596ec4da..11ca058944e9e 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -48,12 +48,12 @@ void AP_Periph_FW::rcout_init() #if HAL_PWM_COUNT > 0 for (uint8_t i=0; i 0 - const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1); + const SRV_Channel::Function function = SRV_Channel::Function(SRV_Channel::k_rcin1 + actuator_id - 1); SRV_Channels::set_output_norm(function, command_value); rcout_has_new_data_to_update = true; @@ -126,7 +126,7 @@ void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_v void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value) { #if HAL_PWM_COUNT > 0 - const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1); + const SRV_Channel::Function function = SRV_Channel::Function(SRV_Channel::k_rcin1 + actuator_id - 1); SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5)); rcout_has_new_data_to_update = true; @@ -204,7 +204,7 @@ void AP_Periph_FW::sim_update_actuator(uint8_t actuator_id) if ((sim_actuator.mask & (1U<