ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

You can give a remote_node_name when creating a SyncParametersClient:

SyncParametersClient(
    rclcpp::Node::SharedPtr node,
    const std::string & remote_node_name = "",
    const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)

So in NODE 1 you can do :

rclcpp::SyncParametersClient::SharedPtr parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node, "node2");

You can give a remote_node_name when creating a SyncParametersClient:

SyncParametersClient(
    rclcpp::Node::SharedPtr node,
    const std::string & remote_node_name = "",
    const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)

So in NODE 1 you can do :

rclcpp::SyncParametersClient::SharedPtr parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node, "node2");

edit: If you want to catch parameter changes during run time, you might want to play with parameters events. Because from what I tried (very quickly, might be wrong), NODE 1 is going to wait for NODE 2 to be launched at while (!parameters_client->wait_for_service(1s)). So you'll have to launch NODE 2 first but then in NODE 2 you only check parameters once in the main and since NODE 1 hasn't set them yet, you won't receive them.

You can give a remote_node_name when creating a SyncParametersClient:

SyncParametersClient(
    rclcpp::Node::SharedPtr node,
    const std::string & remote_node_name = "",
    const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters)

So in NODE 1 you can do :

rclcpp::SyncParametersClient::SharedPtr parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node, "node2");

edit: If you want to catch parameter changes during run time, you might want to play with parameters events. Because from what I tried (very quickly, might be wrong), NODE 1 is going to wait for NODE 2 to be launched at while (!parameters_client->wait_for_service(1s)). So you'll have to launch NODE 2 first but then in NODE 2 you only check parameters once in the main and since NODE 1 hasn't set them yet, you won't receive them.

edit 2: Just in case, you can find examples about this in the demos pkg.