Cannot listen for parameter changes
rosterloh opened this issue · 4 comments
I've been trying to implement a ParameterEventHandler for a parameter provided by an mcu running micro-ROS as in this tutorial. Callbacks come in for 'normal' ros nodes but I don't ever get anything from micro-ROS. Is this expected?
System information:
- OS: Debian Bullseye
- ROS 2: Humble
- Version: main
Hello @rosterloh I will need some more details about your implementation, how are you creating the subscriber?
Hi @pablogs9, sorry I thought implementation was clear from the tutorial link
#include <memory>
#include "rclcpp/rclcpp.hpp"
class NodeWatchingParameters : public rclcpp::Node
{
public:
NodeWatchingParameters()
: Node("node_watching_parameters")
{
param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);
auto cb = [this](const rclcpp::Parameter & p) {
RCLCPP_INFO(
this->get_logger(), "Received an update to parameter \"%s\" of type: %s: \"%.02lf\"",
p.get_name().c_str(),
p.get_type_name().c_str(),
p.as_double());
};
auto remote_node_name = std::string("micro_ros_node");
auto remote_param_name = std::string("a_double_param");
cb_handle_ = param_subscriber_->add_parameter_callback(remote_param_name, cb, remote_node_name);
}
private:
std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<NodeWatchingParameters>());
rclcpp::shutdown();
return 0;
}
Sorry for the confusion, I thought that you were subscribing in the micro-ROS side.
In this case, the RCLC parameter library has an option for enabling the notifications: https://docs.vulcanexus.org/en/latest/rst/microros_documentation/user_api/user_api_parameter_server.html#options