AP_Mount: 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 3c653e4ed6
commit b79644c64a
2 changed files with 5 additions and 5 deletions

View File

@ -203,6 +203,6 @@ void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad)
// move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10
void AP_Mount_Servo::move_servo(uint8_t function_idx, int16_t angle, int16_t angle_min, int16_t angle_max)
{
SRV_Channels::move_servo((SRV_Channel::Aux_servo_function_t)function_idx, angle, angle_min, angle_max);
SRV_Channels::move_servo((SRV_Channel::Function)function_idx, angle, angle_min, angle_max);
}
#endif // HAL_MOUNT_SERVO_ENABLED

View File

@ -59,10 +59,10 @@ private:
const bool requires_stabilization;
// SRV_Channel - different id numbers are used depending upon the instance number
SRV_Channel::Aux_servo_function_t _roll_idx; // SRV_Channel mount roll function index
SRV_Channel::Aux_servo_function_t _tilt_idx; // SRV_Channel mount tilt function index
SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index
SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index
SRV_Channel::Function _roll_idx; // SRV_Channel mount roll function index
SRV_Channel::Function _tilt_idx; // SRV_Channel mount tilt function index
SRV_Channel::Function _pan_idx; // SRV_Channel mount pan function index
SRV_Channel::Function _open_idx; // SRV_Channel mount open function index
Vector3f _angle_bf_output_rad; // final body frame output angle in radians
};