AR_Motors: rename SRV_Channel::Aux_servo_function_t to SRV_Channel::Function

This commit is contained in:
Peter Barker 2025-01-16 15:43:37 +11:00 committed by Peter Barker
parent 4130187249
commit 5f9701bb67
2 changed files with 7 additions and 7 deletions

View File

@ -206,7 +206,7 @@ void AP_MotorsUGV::setup_servo_output()
// omni motors set in power percent so -100 ... 100
for (uint8_t i=0; i<AP_MOTORS_NUM_MOTORS_MAX; i++) {
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i);
SRV_Channel::Function function = SRV_Channels::get_motor_function(i);
SRV_Channels::set_angle(function, 100);
}
@ -520,7 +520,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const
}
// check all omni motor outputs have been configured
for (uint8_t i=0; i<_motors_num; i++) {
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::function_assigned(function)) {
if (report) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: servo function %u unassigned", function);
@ -681,7 +681,7 @@ void AP_MotorsUGV::add_omni_motor_num(int8_t motor_num)
// ensure a valid motor number is provided
if (motor_num >= 0 && motor_num < AP_MOTORS_NUM_MOTORS_MAX) {
uint8_t chan;
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);
if (!SRV_Channels::find_channel(function, chan)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
@ -975,7 +975,7 @@ void AP_MotorsUGV::output_omni(bool armed, float steering, float throttle, float
}
// output throttle value to main throttle channel, left throttle or right throttle. throttle should be scaled from -100 to 100
void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt)
void AP_MotorsUGV::output_throttle(SRV_Channel::Function function, float throttle, float dt)
{
// sanity check servo function
if (function != SRV_Channel::k_throttle && function != SRV_Channel::k_throttleLeft && function != SRV_Channel::k_throttleRight && function != SRV_Channel::k_motor1 && function != SRV_Channel::k_motor2 && function != SRV_Channel::k_motor3 && function!= SRV_Channel::k_motor4) {
@ -1110,7 +1110,7 @@ float AP_MotorsUGV::get_scaled_throttle(float throttle) const
}
// use rate controller to achieve desired throttle
float AP_MotorsUGV::get_rate_controlled_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt)
float AP_MotorsUGV::get_rate_controlled_throttle(SRV_Channel::Function function, float throttle, float dt)
{
// require non-zero dt
if (!is_positive(dt)) {

View File

@ -172,7 +172,7 @@ private:
// output throttle (-100 ~ +100) to a throttle channel. Sets relays if required
// dt is the main loop time interval and is required when rate control is required
void output_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt = 0.0f);
void output_throttle(SRV_Channel::Function function, float throttle, float dt = 0.0f);
// output for sailboat's mainsail in the range of 0 to 100 and wing sail in the range +- 100
void output_sail();
@ -190,7 +190,7 @@ private:
float get_scaled_throttle(float throttle) const;
// use rate controller to achieve desired throttle
float get_rate_controlled_throttle(SRV_Channel::Aux_servo_function_t function, float throttle, float dt);
float get_rate_controlled_throttle(SRV_Channel::Function function, float throttle, float dt);
// external references
AP_WheelRateControl &_rate_controller;