Skip to content

Commit

Permalink
Use non-blocking get_params function on update
Browse files Browse the repository at this point in the history
  • Loading branch information
KentaKato committed Jul 10, 2024
1 parent 18ce11a commit 4e84b06
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,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
Expand Down
2 changes: 1 addition & 1 deletion pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -419,7 +419,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)
{
Expand Down

0 comments on commit 4e84b06

Please sign in to comment.