From 5f9701bb673d12c0182629f0b41083f6889b5c1e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 16 Jan 2025 15:43:37 +1100 Subject: [PATCH] AR_Motors: rename SRV_Channel::Aux_servo_function_t to SRV_Channel::Function --- libraries/AR_Motors/AP_MotorsUGV.cpp | 10 +++++----- libraries/AR_Motors/AP_MotorsUGV.h | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 4b63101d5f..71536a7ad5 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -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= 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)) { diff --git a/libraries/AR_Motors/AP_MotorsUGV.h b/libraries/AR_Motors/AP_MotorsUGV.h index 45df9fe2b5..6d26e3b9b4 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.h +++ b/libraries/AR_Motors/AP_MotorsUGV.h @@ -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;