diff --git a/pid_controller/include/pid_controller/pid_controller.hpp b/pid_controller/include/pid_controller/pid_controller.hpp index 93a2152fe4..a34dc9f87f 100644 --- a/pid_controller/include/pid_controller/pid_controller.hpp +++ b/pid_controller/include/pid_controller/pid_controller.hpp @@ -64,6 +64,10 @@ class PidController : public controller_interface::ChainableControllerInterface PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override; + PID_CONTROLLER__VISIBILITY_PUBLIC + controller_interface::CallbackReturn on_cleanup( + const rclcpp_lifecycle::State & previous_state) override; + PID_CONTROLLER__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure( const rclcpp_lifecycle::State & previous_state) override; @@ -123,6 +127,7 @@ class PidController : public controller_interface::ChainableControllerInterface bool on_set_chained_mode(bool chained_mode) override; // internal methods + void update_parameters(); controller_interface::CallbackReturn configure_parameters(); private: diff --git a/pid_controller/src/pid_controller.cpp b/pid_controller/src/pid_controller.cpp index 53799782ed..fc86c6e904 100644 --- a/pid_controller/src/pid_controller.cpp +++ b/pid_controller/src/pid_controller.cpp @@ -89,9 +89,18 @@ controller_interface::CallbackReturn PidController::on_init() return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::CallbackReturn PidController::configure_parameters() +void PidController::update_parameters() { + if (!param_listener_->is_old(params_)) + { + return; + } params_ = param_listener_->get_params(); +} + +controller_interface::CallbackReturn PidController::configure_parameters() +{ + update_parameters(); if (!params_.reference_and_state_dof_names.empty()) { @@ -140,6 +149,15 @@ controller_interface::CallbackReturn PidController::configure_parameters() return CallbackReturn::SUCCESS; } +controller_interface::CallbackReturn PidController::on_cleanup( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + reference_and_state_dof_names_.clear(); + pids_.clear(); + + return CallbackReturn::SUCCESS; +} + controller_interface::CallbackReturn PidController::on_configure( const rclcpp_lifecycle::State & /*previous_state*/) { @@ -404,6 +422,9 @@ controller_interface::return_type PidController::update_reference_from_subscribe controller_interface::return_type PidController::update_and_write_commands( const rclcpp::Time & time, const rclcpp::Duration & period) { + // check for any parameter updates + update_parameters(); + if (params_.use_external_measured_states) { const auto measured_state = *(measured_state_.readFromRT());