diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 82d9c94aab..1f7dcd247f 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -144,9 +144,8 @@ controller_interface::return_type JointTrajectoryController::update( } auto logger = this->get_node()->get_logger(); // update dynamic parameters - if (param_listener_->is_old(params_)) + if (param_listener_->try_get_params(params_)) { - params_ = param_listener_->get_params(); default_tolerances_ = get_segment_tolerances(logger, params_); // update the PID gains // variable use_closed_loop_pid_adapter_ is updated in on_configure only diff --git a/pid_controller/src/pid_controller.cpp b/pid_controller/src/pid_controller.cpp index 032dc1d666..c3a0629f2b 100644 --- a/pid_controller/src/pid_controller.cpp +++ b/pid_controller/src/pid_controller.cpp @@ -474,7 +474,7 @@ controller_interface::return_type PidController::update_and_write_commands( const rclcpp::Time & time, const rclcpp::Duration & period) { // check for any parameter updates - update_parameters(); + param_listener_->try_get_params(params_); if (params_.use_external_measured_states) {