You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Trying to launch Nav2 nodes while specifying the name with the command line option __node:=some_node_name causes duplicate nodes to be created with the same name. This is because all nodes created in the process inherit those command line options.
This can be triggered by using the launch_ros.actions.Node with the optional node_name argument or the launch_ros.actions.LifecycleNode (which has a mandatory node_name argument) or just by creating the node with ros2 run nav2_amcl amcl __node:=amcl.
The immediate symptom of this is a command line warning such as:
[WARN] [rcl.logging_rosout]: 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.
And this causes unpredictable behavior that I have not fully characterized but are bad.
And you can see the multiple nodes with ros2 node list:
with ros2 run nav2_amcl amcl running:
ros2 node list
/amcl
/amcl_rclcpp_node
/amcl_map_client
running with ros2 run nav2_amcl amcl __node:=amcl
ros2 node list
/amcl
/amcl
/amcl
Further, ros2 node info can only introspect one of those nodes ros2/ros2cli#279
This issue exists in many places within Navigation2. One place is in lifecycle_node.cpp, where the Node constructor is invoked: rclcpp_node_ = std::make_shared<rclcpp::Node>(node_name + "_rclcpp_node", namespace_); Even though this line looks like it should create a node with the globally unique name "amcl_rclcpp_node", that name is overridden in the constructor with the node name passed on the command line "amcl".
Some possible remedies:
Instead of using the rclcpp::Node constructor, if a plain node object is needed and the parent is a rclcpp::Node (not a lifecycle node), use Node::create_sub_node. This is nice because the name you pass is concatenated with the owning node's name.
Pass NodeOptions().use_global_arguments(false) to the subnode's constructor. You must still pass the subnode a globally unique name.
Pass a namespace to the subnode constructor.
The text was updated successfully, but these errors were encountered:
Trying to launch Nav2 nodes while specifying the name with the command line option
__node:=some_node_name
causes duplicate nodes to be created with the same name. This is because all nodes created in the process inherit those command line options.This can be triggered by using the
launch_ros.actions.Node
with the optionalnode_name
argument or thelaunch_ros.actions.LifecycleNode
(which has a mandatorynode_name
argument) or just by creating the node withros2 run nav2_amcl amcl __node:=amcl
.The immediate symptom of this is a command line warning such as:
And this causes unpredictable behavior that I have not fully characterized but are bad.
And you can see the multiple nodes with
ros2 node list
:with
ros2 run nav2_amcl amcl
running:running with
ros2 run nav2_amcl amcl __node:=amcl
Further,
ros2 node info
can only introspect one of those nodes ros2/ros2cli#279This issue exists in many places within Navigation2. One place is in
lifecycle_node.cpp
, where the Node constructor is invoked:rclcpp_node_ = std::make_shared<rclcpp::Node>(node_name + "_rclcpp_node", namespace_);
Even though this line looks like it should create a node with the globally unique name "amcl_rclcpp_node", that name is overridden in the constructor with the node name passed on the command line "amcl".Some possible remedies:
rclcpp::Node
constructor, if a plain node object is needed and the parent is arclcpp::Node
(not a lifecycle node), useNode::create_sub_node
. This is nice because the name you pass is concatenated with the owning node's name.NodeOptions().use_global_arguments(false)
to the subnode's constructor. You must still pass the subnode a globally unique name.The text was updated successfully, but these errors were encountered: