Skip to content

Commit 92e7139

Browse files
committed
Update PIDController to enable parameter updates.
1 parent 486c078 commit 92e7139

File tree

2 files changed

+27
-1
lines changed

2 files changed

+27
-1
lines changed

pid_controller/include/pid_controller/pid_controller.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,10 @@ class PidController : public controller_interface::ChainableControllerInterface
6464
PID_CONTROLLER__VISIBILITY_PUBLIC
6565
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
6666

67+
PID_CONTROLLER__VISIBILITY_PUBLIC
68+
controller_interface::CallbackReturn on_cleanup(
69+
const rclcpp_lifecycle::State & previous_state) override;
70+
6771
PID_CONTROLLER__VISIBILITY_PUBLIC
6872
controller_interface::CallbackReturn on_configure(
6973
const rclcpp_lifecycle::State & previous_state) override;
@@ -123,6 +127,7 @@ class PidController : public controller_interface::ChainableControllerInterface
123127
bool on_set_chained_mode(bool chained_mode) override;
124128

125129
// internal methods
130+
void update_parameters();
126131
controller_interface::CallbackReturn configure_parameters();
127132

128133
private:

pid_controller/src/pid_controller.cpp

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,9 +89,18 @@ controller_interface::CallbackReturn PidController::on_init()
8989
return controller_interface::CallbackReturn::SUCCESS;
9090
}
9191

92-
controller_interface::CallbackReturn PidController::configure_parameters()
92+
void PidController::update_parameters()
9393
{
94+
if (!param_listener_->is_old(params_))
95+
{
96+
return;
97+
}
9498
params_ = param_listener_->get_params();
99+
}
100+
101+
controller_interface::CallbackReturn PidController::configure_parameters()
102+
{
103+
update_parameters();
95104

96105
if (!params_.reference_and_state_dof_names.empty())
97106
{
@@ -140,6 +149,15 @@ controller_interface::CallbackReturn PidController::configure_parameters()
140149
return CallbackReturn::SUCCESS;
141150
}
142151

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+
143161
controller_interface::CallbackReturn PidController::on_configure(
144162
const rclcpp_lifecycle::State & /*previous_state*/)
145163
{
@@ -404,6 +422,9 @@ controller_interface::return_type PidController::update_reference_from_subscribe
404422
controller_interface::return_type PidController::update_and_write_commands(
405423
const rclcpp::Time & time, const rclcpp::Duration & period)
406424
{
425+
// check for any parameter updates
426+
update_parameters();
427+
407428
if (params_.use_external_measured_states)
408429
{
409430
const auto measured_state = *(measured_state_.readFromRT());

0 commit comments

Comments
 (0)