Skip to content

Commit 0f76355

Browse files
committed
Add deprecated message for the old anti-windup
1 parent e89ac18 commit 0f76355

File tree

1 file changed

+21
-0
lines changed

1 file changed

+21
-0
lines changed

control_toolbox/src/pid_ros.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,13 @@ bool PidROS::initialize_from_ros_parameters()
238238
set_parameter_event_callback();
239239
}
240240

241+
if (antiwindup_strat_str == "none")
242+
{
243+
std::cout << "Old anti-windup technique is deprecated. "
244+
"This option will be removed by the ROS 2 Kilted Kaiju release."
245+
<< std::endl;
246+
}
247+
241248
AntiwindupStrategy antiwindup_strat(antiwindup_strat_str);
242249

243250
pid_.initialize(
@@ -283,6 +290,13 @@ void PidROS::initialize_from_args(
283290
}
284291
else
285292
{
293+
if (antiwindup_strat == AntiwindupStrategy::NONE)
294+
{
295+
std::cout << "Old anti-windup technique is deprecated. "
296+
"This option will be removed by the ROS 2 Kilted Kaiju release."
297+
<< std::endl;
298+
}
299+
286300
pid_.initialize(
287301
p, i, d, i_max, i_min, u_max, u_min, trk_tc, saturation, antiwindup, antiwindup_strat);
288302

@@ -353,6 +367,13 @@ void PidROS::set_gains(
353367
}
354368
else
355369
{
370+
if (antiwindup_strat == AntiwindupStrategy::NONE)
371+
{
372+
std::cout << "Old anti-windup technique is deprecated. "
373+
"This option will be removed by the ROS 2 Kilted Kaiju release."
374+
<< std::endl;
375+
}
376+
356377
node_params_->set_parameters(
357378
{rclcpp::Parameter(param_prefix_ + "p", p), rclcpp::Parameter(param_prefix_ + "i", i),
358379
rclcpp::Parameter(param_prefix_ + "d", d),

0 commit comments

Comments
 (0)