AP_Motors: rename SRV_Channel::Aux_servo_function_t to SRV_Channel::Function

This commit is contained in:
Peter Barker 2025-01-16 15:43:36 +11:00 committed by Peter Barker
parent f5aae89f41
commit 3c653e4ed6
5 changed files with 10 additions and 10 deletions

View File

@ -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

View File

@ -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);
}

View File

@ -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;

View File

@ -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;

View File

@ -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<<chan) & _motor_pwm_scaled.mask) {
// note that PWM_MIN/MAX has been forced to 1000/2000
SRV_Channels::set_output_scaled(function, float(pwm) - _motor_pwm_scaled.offset);
@ -118,7 +118,7 @@ void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
*/
void AP_Motors::rc_write_angle(uint8_t chan, int16_t angle_cd)
{
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_scaled(function, angle_cd);
}
@ -210,7 +210,7 @@ uint32_t AP_Motors::motor_mask_to_srv_channel_mask(uint32_t mask) const
for (uint8_t i = 0; i < 32; i++) {
uint32_t bit = 1UL << i;
if (mask & bit) {
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i);
SRV_Channel::Function function = SRV_Channels::get_motor_function(i);
mask2 |= SRV_Channels::get_output_channel_mask(function);
}
}
@ -224,7 +224,7 @@ void AP_Motors::add_motor_num(int8_t motor_num)
{
// ensure valid motor number is provided
if (motor_num >= 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);
}
}