@@ -89,9 +89,18 @@ controller_interface::CallbackReturn PidController::on_init()
89
89
return controller_interface::CallbackReturn::SUCCESS;
90
90
}
91
91
92
- controller_interface::CallbackReturn PidController::configure_parameters ()
92
+ void PidController::update_parameters ()
93
93
{
94
+ if (!param_listener_->is_old (params_))
95
+ {
96
+ return ;
97
+ }
94
98
params_ = param_listener_->get_params ();
99
+ }
100
+
101
+ controller_interface::CallbackReturn PidController::configure_parameters ()
102
+ {
103
+ update_parameters ();
95
104
96
105
if (!params_.reference_and_state_dof_names .empty ())
97
106
{
@@ -140,6 +149,15 @@ controller_interface::CallbackReturn PidController::configure_parameters()
140
149
return CallbackReturn::SUCCESS;
141
150
}
142
151
152
+ controller_interface::CallbackReturn PidController::on_cleanup (
153
+ const rclcpp_lifecycle::State & /* previous_state*/ )
154
+ {
155
+ reference_and_state_dof_names_.clear ();
156
+ pids_.clear ();
157
+
158
+ return CallbackReturn::SUCCESS;
159
+ }
160
+
143
161
controller_interface::CallbackReturn PidController::on_configure (
144
162
const rclcpp_lifecycle::State & /* previous_state*/ )
145
163
{
@@ -404,6 +422,9 @@ controller_interface::return_type PidController::update_reference_from_subscribe
404
422
controller_interface::return_type PidController::update_and_write_commands (
405
423
const rclcpp::Time & time, const rclcpp::Duration & period)
406
424
{
425
+ // check for any parameter updates
426
+ update_parameters ();
427
+
407
428
if (params_.use_external_measured_states )
408
429
{
409
430
const auto measured_state = *(measured_state_.readFromRT ());
0 commit comments