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)