Skip to content

Feat: add user callback #250

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 9 commits into from
Jun 5, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -422,6 +422,11 @@ if (param_listener->is_old(params_)) {
}
```

Alternatively, you can bind a callback function that triggers whenever a parameter is updated. When activated, the callback receives the updated parameters as an argument.
```c++
parameter_listener.setUserCallback([this](const auto& params) { reconfigure_callback(params); });
```

### Parameter documentation

In some cases, parameters might be unknown only at compile-time, and cannot be part of the generated C++ code. However, for documentation purpose of such parameters, the type `none` was introduced.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ class MinimalPublisher : public rclcpp::Node {

private:
void timer_callback();
void reconfigure_callback(const admittance_controller::Params& params);

rclcpp::TimerBase::SharedPtr timer_;
std::shared_ptr<admittance_controller::ParamListener> param_listener_;
Expand Down
15 changes: 15 additions & 0 deletions example/src/minimal_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ MinimalPublisher::MinimalPublisher(const rclcpp::NodeOptions& options)
500ms, std::bind(&MinimalPublisher::timer_callback, this));
param_listener_ =
std::make_shared<ParamListener>(get_node_parameters_interface());
param_listener_->setUserCallback(
[this](const auto& params) { reconfigure_callback(params); });
params_ = param_listener_->get_params();

[[maybe_unused]] StackParams s_params = param_listener_->get_stack_params();
Expand Down Expand Up @@ -71,4 +73,17 @@ void MinimalPublisher::timer_callback() {
}
}

void MinimalPublisher::reconfigure_callback(
const admittance_controller::Params& params) {
RCLCPP_INFO(get_logger(), "Reconfigure callback fired!");
RCLCPP_INFO(get_logger(), "New control frame parameter is: '%s'",
params.control.frame.id.c_str());
RCLCPP_INFO(get_logger(), "fixed string is: '%s'",
std::string{params.fixed_string}.c_str());
const auto fixed_array = params.fixed_array;
for (auto d : fixed_array) {
RCLCPP_INFO(get_logger(), "value: '%s'", std::to_string(d).c_str());
}
}

} // namespace admittance_controller
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,9 @@ struct StackParams {
{%- endif %}
updated_params.__stamp = clock_.now();
update_internal_params(updated_params);
if (user_callback_) {
user_callback_(updated_params);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The variable is called update_params. But I believe it contains all parameters, not just the ones that got updated right?

Would it be an idea to only supply the actually updated parameters? Otherwise the logging statements (like in the example) would be really verbose if you have multiple parameters. And from a log-reader standpoint you still don't have a clue what actually changed.

Copy link
Collaborator

@pac48 pac48 Jun 3, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That is a good point. The user callback signature could be changed to const std::vector<rclcpp::Parameter> &parameters, which is only the updated parameters. The variable parameters is in scope. So we could change it to

if (user_callback_) {
  user_callback_(parameters);
}

@YannickdeHoop Does this seem reasonable? The one thing I like about having all of the parameters is that dependencies between parameters could be considered in the callback, e.g. the user sets parameter A, but B was not set, so don't trigger some action.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I get the point and I understand that this is a valid use case. But in my implementation I'd like to have all parameters not only the one that i updated. So I suggest to create an issue to implement another user_callback function that returns only the updated params.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, can do!

One last question: is setUserCallback the right name here to differentiate these two use cases?
Because once this is in, it's harder to rename because of backward compatibility etc.

}
return rsl::to_parameter_result_msg({});
}

Expand All @@ -208,6 +211,15 @@ struct StackParams {
update_internal_params(updated_params);
}

using userParameterUpdateCB = std::function<void(const Params&)>;
void setUserCallback(const userParameterUpdateCB& callback){
user_callback_ = callback;
}

void clearUserCallback(){
user_callback_ = {};
}

private:
void update_internal_params(Params updated_params) {
std::lock_guard<std::mutex> lock(mutex_);
Expand All @@ -219,6 +231,7 @@ struct StackParams {
rclcpp::Clock clock_;
std::shared_ptr<rclcpp::node_interfaces::OnSetParametersCallbackHandle> handle_;
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_;
userParameterUpdateCB user_callback_;

// rclcpp::Logger cannot be default-constructed
// so we must provide a initialization here even though
Expand Down
Loading