From 3c653e4ed64a3154ad97c761a1dcdf3e371129a7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 16 Jan 2025 15:43:36 +1100 Subject: [PATCH] AP_Motors: rename SRV_Channel::Aux_servo_function_t to SRV_Channel::Function --- libraries/AP_Motors/AP_MotorsHeli_RSC.h | 4 ++-- libraries/AP_Motors/AP_MotorsHeli_Swash.cpp | 4 ++-- libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp | 2 +- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- libraries/AP_Motors/AP_Motors_Class.cpp | 8 ++++---- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 47fa68f8ad..6149ab6044 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -22,7 +22,7 @@ public: friend class AP_MotorsHeli_Dual; friend class AP_MotorsHeli_Quad; - AP_MotorsHeli_RSC(SRV_Channel::Aux_servo_function_t aux_fn, + AP_MotorsHeli_RSC(SRV_Channel::Function aux_fn, uint8_t default_channel, uint8_t inst) : _instance(inst), @@ -117,7 +117,7 @@ private: const uint8_t _instance; // channel setup for aux function - const SRV_Channel::Aux_servo_function_t _aux_fn; + const SRV_Channel::Function _aux_fn; const uint8_t _default_channel; // internal variables diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp index 49eff5b895..b59318649c 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp @@ -198,7 +198,7 @@ void AP_MotorsHeli_Swash::add_servo_raw(uint8_t num, float roll, float pitch, fl _collectiveFactor[num] = collective; // Setup output function - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(_motor_num[num]); + SRV_Channel::Function function = SRV_Channels::get_motor_function(_motor_num[num]); SRV_Channels::set_aux_channel_default(function, _motor_num[num]); // outputs are defined on a -500 to 500 range for swash servos @@ -272,7 +272,7 @@ void AP_MotorsHeli_Swash::output() void AP_MotorsHeli_Swash::rc_write(uint8_t chan, float swash_in) { uint16_t pwm = (uint16_t)(1500 + 500 * swash_in); - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan); + SRV_Channel::Function function = SRV_Channels::get_motor_function(chan); SRV_Channels::set_output_pwm_trimmed(function, pwm); } diff --git a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp index d22c75d1e0..491b09ab4b 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp @@ -261,7 +261,7 @@ void AP_MotorsMatrix_6DoF_Scripting::add_motor(int8_t motor_num, float roll_fact _test_order[motor_num] = testing_order; // ensure valid motor number is provided - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num); + SRV_Channel::Function function = SRV_Channels::get_motor_function(motor_num); SRV_Channels::set_aux_channel_default(function, motor_num); uint8_t chan; diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 7269918b7a..67a0198a53 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -806,7 +806,7 @@ bool AP_MotorsMulticopter::arming_checks(size_t buflen, char *buffer) const continue; } uint8_t chan; - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i); + SRV_Channel::Function function = SRV_Channels::get_motor_function(i); if (!SRV_Channels::find_channel(function, chan)) { hal.util->snprintf(buffer, buflen, "no SERVOx_FUNCTION set to Motor%u", i + 1); return false; diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 42d7deebda..f25b905a68 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -104,7 +104,7 @@ void AP_Motors::set_radio_passthrough(float roll_input, float pitch_input, float */ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm) { - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan); + SRV_Channel::Function function = SRV_Channels::get_motor_function(chan); if ((1U<= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS) { - SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num); + SRV_Channel::Function function = SRV_Channels::get_motor_function(motor_num); SRV_Channels::set_aux_channel_default(function, motor_num); } }