Ask Your Question
1

How to get ROS2 parameter hosted by another Node

asked 2019-12-23 11:58:57 -0600

mequi gravatar image

Hello,

I have been looking through the documentation and can not find any means to get or set parameters of other nodes than the one that has declared the parameters. Is this by design or is there a way to get the parameter with something like node.get_parameter(other_node_name, parameter_name)? I currently have parameters duplicated across configuration files because I can't figure out how to get the nodes to reach each others configurations. Any help is greatly appreciated!

I am using ROS2 dashing.

Thanks

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-01-25 05:28:28 -0600

marguedas gravatar image

In ROS 2 parameters are available via service interfaces:

root@d0a03d7984eb:/# ros2 run demo_nodes_cpp listener &
root@d0a03d7984eb:/# ros2 service list
/listener/describe_parameters
/listener/get_parameter_types
/listener/get_parameters
/listener/list_parameters
/listener/set_parameters
/listener/set_parameters_atomically

In rclpy I believe there is no helper and you need to create a service client yourself and call it, similar to what is done in ros2 service

In rclcpp there is are ParameterClient classes on which you can call functions like get_parameters and it will handle the service calls

the use looks like:

auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(my_node, "remote_node_name");
while (!parameters_client->wait_for_service(1s)) {
  if (!rclcpp::ok()) {
    RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
    rclcpp::shutdown();
  }
  RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
}
auto parameters = parameters_client->get_parameters({"remote_param1", "remote_param2"});

you can then access them:

std::stringstream ss;
// Get a few of the parameters just set.
for (auto & parameter : parameters)
{
  ss << "\nParameter name: " << parameter.get_name();
  ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
    parameter.value_to_string();
}

There is also a non-blocking / asynchronous version rclcpp::AsyncParametersClient

edit flag offensive delete link more

Comments

@marguedas I tried it with rclpy, but no luck. Do you mind to give me a sample in python for this? Also, seems there is no SyncParametersClient ore AsyncParametersClient like method in rclpy ? Thank you!

lin404 gravatar imagelin404 ( 2020-02-05 00:17:44 -0600 )edit

Also, seems there is no SyncParametersClient ore AsyncParametersClient like method in rclpy ?

Yes that is what I tried to say when saying " there is no helper and you need to create a service client yourself and call it". The fact thatthey don't exist make the example more verbose than in C++.

Do you mind to give me a sample in python for this?

I replied on https://answers.ros.org/question/3433... with a correction to your example

marguedas gravatar imagemarguedas ( 2020-02-05 03:28:15 -0600 )edit

@marguedas Thanks for your help a lot!

lin404 gravatar imagelin404 ( 2020-02-05 18:18:00 -0600 )edit

Your Answer

Please start posting anonymously - your entry will be published after you log in or create a new account.

Add Answer

Question Tools

1 follower

Stats

Asked: 2019-12-23 11:58:57 -0600

Seen: 31 times

Last updated: Jan 25