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

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/163/files#diff-df7db447d3b09c67c5487a923f56a445R423

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.

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/163/files#diff-df7db447d3b09c67c5487a923f56a445R423

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 std::string & node_namespace,
    rclcpp::NodeOptions options)
  : rclcpp::Node(node_name, node_namespace, options)
  {}
};

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

  rclcpp::executors::MultiThreadedExecutor executor;

  auto options = rclcpp::NodeOptions().use_global_arguments(false);
  auto node1 = std::make_shared<MyNode>("my_node1", "ns", options);
  auto node2 = std::make_shared<MyNode>("my_node2", "ns", options);

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

  for (auto name : node1->get_node_names()) {if (!name.empty()) printf("'%s'\n", name.c_str());}

  executor.spin();

  return 0;
}

So if you take the above and run the aforementioned launch code, it will not change your node names.

However, it may prevent launch from working correctly because launch_ros.actions.LifecycleNode uses the given node name and namespace to know how to monitor the node for lifecycle state changes.

Long term, launch should be updated to better support executables with multiple nodes within them.

In the meantime, however, for your specific use case where you have a lifecycle and non-lifecycle node in the same process, I'd recommend something like this:

#include <memory>
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>

class MyNode : public rclcpp::Node
{
public:
  template<typename... Args>
  explicit
  MyNode(Args&&... args) : rclcpp::Node(std::forward<Args>(args)...) {}
};

class MyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
  template<typename... Args>
  explicit
  MyLifecycleNode(Args&&... args)
  : rclcpp_lifecycle::LifecycleNode(std::forward<Args>(args)...)
  {}
};

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

  rclcpp::executors::MultiThreadedExecutor executor;

  auto node1 =
    std::make_shared<MyNode>("normal", "", rclcpp::NodeOptions().use_global_arguments(false));
  auto node2 = std::make_shared<MyLifecycleNode>("lifecycle");

  executor.add_node(node1);
  executor.add_node(node2->get_node_base_interface());

  for (auto name : node1->get_node_names()) {if (!name.empty()) printf("'%s'\n", name.c_str());}

  executor.spin();

  return 0;
}

Which creates a normal node with use_global_arguments as false, and a lifecycle node with the default of true. In this case the node name given to launch will effect the lifecycle node but leave the normal one untouched. So if you do something like this:

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

You'll get something like this:

'normal'
'my_node_instance1'

Which allows you to avoid the duplicate names issue, allows you to control the lifecycle node's name from launch, and therefore for launch to monitor it remotely for state changes.


There is a lingering and related issue (or actually two), which is that targeting nodes with specific settings from the command line only considers the node name and not the fully qualified node name which would also include the namespace, see: https://github.com/ros2/rcl/issues/296 and that rclcpp::Node::get_node_names() does not return the fully qualified node name (it does not include the namespace) which you may have noticed in the last example's output, see: https://github.com/ros2/rclcpp/issues/643 (we could use help with implementing this ;) )