Skip to content

Commit b58af5a

Browse files
authored
Remove legacy and deprecated PID parameters (#1845)
1 parent 92c2582 commit b58af5a

File tree

5 files changed

+15
-33
lines changed

5 files changed

+15
-33
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1890,8 +1890,8 @@ void JointTrajectoryController::update_pids()
18901890
const auto & gains = params_.gains.joints_map.at(params_.joints.at(map_cmd_to_joints_[i]));
18911891
control_toolbox::AntiWindupStrategy antiwindup_strat;
18921892
antiwindup_strat.set_type(gains.antiwindup_strategy);
1893-
antiwindup_strat.i_max = gains.i_clamp;
1894-
antiwindup_strat.i_min = -gains.i_clamp;
1893+
antiwindup_strat.i_max = gains.i_clamp_max;
1894+
antiwindup_strat.i_min = gains.i_clamp_min;
18951895
antiwindup_strat.error_deadband = gains.error_deadband;
18961896
antiwindup_strat.tracking_time_constant = gains.tracking_time_constant;
18971897
if (pids_[i])

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 6 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -150,11 +150,6 @@ joint_trajectory_controller:
150150
default_value: 0.0,
151151
description: "Derivative gain :math:`k_d` for PID"
152152
}
153-
i_clamp: {
154-
type: double,
155-
default_value: 0.0,
156-
description: "Integral clamp. Symmetrical in both positive and negative direction."
157-
}
158153
ff_velocity_scale: {
159154
type: double,
160155
default_value: 0.0,
@@ -172,26 +167,24 @@ joint_trajectory_controller:
172167
}
173168
i_clamp_max: {
174169
type: double,
175-
default_value: 0.0,
176-
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
170+
default_value: .inf,
171+
description: "Upper integral clamp."
177172
}
178173
i_clamp_min: {
179174
type: double,
180-
default_value: 0.0,
181-
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
175+
default_value: -.inf,
176+
description: "Lower integral clamp."
182177
}
183178
antiwindup_strategy: {
184179
type: string,
185-
default_value: "legacy",
186-
read_only: true,
180+
default_value: "none",
187181
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
188-
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
182+
'conditional_integration' or 'none'. Note that the 'back_calculation' strategy use the
189183
tracking_time_constant parameter to tune the anti-windup behavior.",
190184
validation: {
191185
one_of<>: [[
192186
"back_calculation",
193187
"conditional_integration",
194-
"legacy",
195188
"none"
196189
]]
197190
}

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -304,9 +304,8 @@ class TrajectoryControllerTest : public ::testing::Test
304304
const rclcpp::Parameter k_p(prefix + ".p", p_value);
305305
const rclcpp::Parameter k_i(prefix + ".i", 0.0);
306306
const rclcpp::Parameter k_d(prefix + ".d", 0.0);
307-
const rclcpp::Parameter i_clamp(prefix + ".i_clamp", 0.0);
308307
const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_value);
309-
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale});
308+
node->set_parameters({k_p, k_i, k_d, ff_velocity_scale});
310309
}
311310
}
312311

pid_controller/src/pid_controller.yaml

Lines changed: 6 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -70,35 +70,26 @@ pid_controller:
7070
default_value: -.inf,
7171
description: "Lower output clamp."
7272
}
73-
antiwindup: {
74-
type: bool,
75-
default_value: false,
76-
description: "[Deprecated, see antiwindup_strategy] Anti-windup functionality. When set to true, limits
77-
the integral error to prevent windup; otherwise, constrains the
78-
integral contribution to the control output. i_clamp_max and
79-
i_clamp_min are applied in both scenarios."
80-
}
8173
i_clamp_max: {
8274
type: double,
83-
default_value: 0.0,
84-
description: "[Deprecated, see antiwindup_strategy] Upper integral clamp."
75+
default_value: .inf,
76+
description: "Upper integral clamp."
8577
}
8678
i_clamp_min: {
8779
type: double,
88-
default_value: 0.0,
89-
description: "[Deprecated, see antiwindup_strategy] Lower integral clamp."
80+
default_value: -.inf,
81+
description: "Lower integral clamp."
9082
}
9183
antiwindup_strategy: {
9284
type: string,
93-
default_value: "legacy",
85+
default_value: "none",
9486
description: "Specifies the anti-windup strategy. Options: 'back_calculation',
95-
'conditional_integration', 'legacy' or 'none'. Note that the 'back_calculation' strategy use the
87+
'conditional_integration' or 'none'. Note that the 'back_calculation' strategy use the
9688
tracking_time_constant parameter to tune the anti-windup behavior.",
9789
validation: {
9890
one_of<>: [[
9991
"back_calculation",
10092
"conditional_integration",
101-
"legacy",
10293
"none"
10394
]]
10495
}

pid_controller/test/test_pid_controller.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,6 @@ TEST_F(PidControllerTest, all_parameters_set_configure_success)
4545
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].p, 1.0);
4646
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].i, 2.0);
4747
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].d, 3.0);
48-
ASSERT_FALSE(controller_->params_.gains.dof_names_map[dof_name].antiwindup);
4948
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].u_clamp_max, 5.0);
5049
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].u_clamp_min, -5.0);
5150
ASSERT_EQ(controller_->params_.gains.dof_names_map[dof_name].feedforward_gain, 0.0);

0 commit comments

Comments
 (0)