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

[ROS2] composition and node names with launch files

asked 2019-02-27 07:57:37 -0500

Myzhar gravatar image

Hi,

I have a container with two nodes using intraprocess communication. One node is "normal", while the other is a lifecycle managed node.

When I use a launch file to start the container both the nodes get the same name and I get this warning: 1551268818.982420326: [rcl.logging_rosout] [WARN] Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.

Is there a way to assign an unique name to each node components?

Thank you

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
8

answered 2019-02-27 16:14:42 -0500

William gravatar image

updated 2019-02-28 16:18:22 -0500

Remapping arguments can be targeted on the command line. There's no functionality in launch_ros for this yet. I had theorized about a Process with Multiple Nodes:

https://github.com/ros2/design/pull/1...

In there I note that's possible to remap name/namespace for each one, e.g. camera1:__ns:=left camera2:__ns:=right. But there's no helper for that in launch. You'd need to figure out the command line arguments yourself and then pass those manually in the launch file.


Edit1:

So, let me make a few examples to explain the current state of affairs.

First consider this:

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>

class MyNode : public rclcpp::Node
{
public:
  MyNode() : rclcpp::Node("my_node")
  {}
};

int main(int argc, char const *argv[])
{
  rclcpp::init(argc, argv);

  rclcpp::executors::MultiThreadedExecutor executor;

  auto node1 = std::make_shared<MyNode>();
  auto node2 = std::make_shared<MyNode>();

  executor.add_node(node1);
  executor.add_node(node2);

  executor.spin();

  return 0;
}

The issue with this is that you run into the problem you reported originally, and you cannot effectively address them from the command line (and therefore also not from launch either).

When you do something like this:

launch_ros.actions.LifecycleNode(
    node_name='my_node_instance1',
    node_namespace='my_ns',
    node_executable='my_exec',
    # ...
)

Then what launch then does is something like my_exec __node:=my_node_instance1 __ns:=/my_ns, which as you've discovered will apply to both nodes (in objects node1 and node2), which still leaves them with the same name.

If you instead did something like this:

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>

class MyNode : public rclcpp::Node
{
public:
  explicit
  MyNode(const std::string & node_name="my_node", const std::string & node_namespace="/")
  : rclcpp::Node(node_name, node_namespace)
  {}
};

int main(int argc, char const *argv[])
{
  rclcpp::init(argc, argv);

  rclcpp::executors::MultiThreadedExecutor executor;

  auto node1 = std::make_shared<MyNode>("my_node1");
  auto node2 = std::make_shared<MyNode>("my_node2");

  executor.add_node(node1);
  executor.add_node(node2);

  executor.spin();

  return 0;
}

The above program can be run in any of these ways:

  • remap a topic my_exec my_node1:chatter:=chatter1 my_node2:chatter:=chatter2
  • change node namespace my_exec my_node1:__ns:=/ns1 my_node2:__ns:=/ns2
  • change node name my_exec my_node1:__node:=foo my_node2:__node:=bar

For this reason, I recommend you always give nodes with in the same process a unique name, so that you can automatically avoid the issue you original reported and so you can address specific settings to them from the command line.

That does not however address the concern you had with launch, if you then again do:

launch_ros.actions.LifecycleNode(
    node_name='my_node_instance1',
    node_namespace='my_ns',
    node_executable='my_exec',
    # ...
)

You'll still end up with a command like my_exec __node:=my_node_instance1 __ns:="my_ns", which will get you back to have two nodes with the same name, and your original issue.

As you suggested in your comments, you can work around this by telling it to not use global arguments, which would at least prevent launch from affecting the node names:

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>

class MyNode : public rclcpp::Node
{
public:
  explicit
  MyNode(
    const std::string & node_name,
    const ...
(more)
edit flag offensive delete link more

Comments

Where do you specify the camera1 and camera2 node names? Another problem that I see is about parameters, having the nodes two different names and different namespace I must create two different YAML files even if they have common parameters... or is there a way to specify common (global) params?

Myzhar gravatar image Myzhar  ( 2019-02-27 16:58:42 -0500 )edit
1

The assumption in that example is that you have a single process which has two nodes, one called camera1 and one called camera2. If the class does not let you set the node name (without remapping) then you might have a use case we didn't think of and don't currently support. I'll edit my answer.

William gravatar image William  ( 2019-02-27 17:17:53 -0500 )edit

Do you think that is possible to use the constructor with use_global_arguments and set it to false to ignore the name passed by the launch file? In this case I do not know where to get the context : http://docs.ros2.org/latest/api/rclcp...

Myzhar gravatar image Myzhar  ( 2019-02-28 02:49:02 -0500 )edit

It seems that setting use_global_arguments to false and using the get_global_default_context function for context I can overwrite the names. Now the problem is that also the __params argument is ignored and parameters are not initialized from YAML. How can I create the param list by myself?

Myzhar gravatar image Myzhar  ( 2019-02-28 05:05:03 -0500 )edit

Finally I made a function to parse the YAML file using RCL. I think that a function that gets a YAML file as input and returns a parameter list should be useful: std::vector<rclcpp::Parameter> createParamsListFromYAML(std::string yaml_file, std::string ros_namespace, std::string node_name)

Myzhar gravatar image Myzhar  ( 2019-02-28 10:35:49 -0500 )edit

I did a bit edit to my answer, hopefully it's helpful for you and others. Yeah you can create your own parameters as you described.

William gravatar image William  ( 2019-02-28 16:19:06 -0500 )edit

Thank you for the very helpful reply... I will work with that in mind... waiting for Lifecycle support for image_transport and tf_broadcaster that is why I have this hybrid multinode configuration ;-)

Myzhar gravatar image Myzhar  ( 2019-02-28 16:28:26 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-02-27 07:57:37 -0500

Seen: 6,369 times

Last updated: Feb 28 '19