From ed1c12c022158b40c8a6ba02e05c428f6b2d9aac Mon Sep 17 00:00:00 2001 From: ViktorCVS Date: Thu, 4 Sep 2025 03:11:57 +0000 Subject: [PATCH] Use i_clamp_max/min in UR controllers Replace gains.i_clamp with gains.i_clamp_max/min for anti-windup. Enables asymmetric integral limits and matches current names. Symmetric configs (max=+M, min=-M) keep the same behavior. --- ur_controllers/src/scaled_joint_trajectory_controller.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index bdc935b0d..01789523a 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -358,8 +358,8 @@ void ScaledJointTrajectoryController::update_pids() const auto& gains = params_.gains.joints_map.at(params_.joints.at(map_cmd_to_joints_[i])); control_toolbox::AntiWindupStrategy antiwindup_strat; antiwindup_strat.set_type(gains.antiwindup_strategy); - antiwindup_strat.i_max = gains.i_clamp; - antiwindup_strat.i_min = -gains.i_clamp; + antiwindup_strat.i_max = gains.i_clamp_max; + antiwindup_strat.i_min = gains.i_clamp_min; antiwindup_strat.error_deadband = gains.error_deadband; antiwindup_strat.tracking_time_constant = gains.tracking_time_constant; if (pids_[i]) {