ros2 / launch

Tools for launching multiple processes and for writing tests involving multiple processes.
Apache License 2.0
124 stars 139 forks source link

Node duplicated when 'name' specified in the .launch.py #704

Open 130s opened 1 year ago

130s commented 1 year ago

Issue report

Required Info:

Steps to reproduce issue

t_launch.py (this causes the issue)

import os
import yaml

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():
    launchdemo = Node(
        name="pick_place_sample2",
        package="get_pose_client",
        # executable="test_trajectory",
        #executable="test_trajectory2",
        executable="pick_place",
        output="screen",
        parameters=[],
    )
    nodes_to_start = [launchdemo]

    return LaunchDescription(nodes_to_start)
#include <string>
#include "rclcpp/rclcpp.hpp"

class PickPlace : public rclcpp::Node {
public:
  PickPlace(std::shared_ptr<rclcpp::Node> move_group_node)
      : Node("pick_place") {} // end of constructor

}; // End of Class

int main(int argc, char **argv) {
  rclcpp::init(argc, argv);
  rclcpp::NodeOptions node_options;
  node_options.automatically_declare_parameters_from_overrides(true);
  auto move_group_node =
      rclcpp::Node::make_shared("move_group_demo", node_options);

  rclcpp::executors::SingleThreadedExecutor planner_executor;
  std::shared_ptr<PickPlace> planner_node =
      std::make_shared<PickPlace>(move_group_node);
  planner_executor.add_node(planner_node);
  planner_executor.spin();

  rclcpp::shutdown();
  return 0;
}

Expected behavior

[INFO] [pick_place-1]: process started with pid [25768]
:
(No error/warning from this node)

Actual behavior

Stdout

[INFO] [pick_place-1]: process started with pid [25768]
[pick_place-1] [WARN] [1681532371.573175635] [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.
$ ros2 node list
WARNING: Be aware that are nodes in the graph that share an exact name, this can have unintended side effects.
:
/pick_place_sample2
/pick_place_sample2
:

Additional information

Seems related answers.ros.org#344141.

Possible workaround

As mentioned answers.ros.org#344141, removing name in Node instance seems to stop the issue.

130s commented 1 year ago

In my report above I noticed a new version of launch was available so tried, but I still get his issue.

$ apt-cache policy ros-foxy-launch
ros-foxy-launch:
  Installed: 0.10.10-1focal.20230306.200955
  Candidate: 0.10.10-1focal.20230306.200955
christophebedard commented 1 year ago

Since Node is from launch_ros, have you tried updating ros-foxy-launch-ros?

130s commented 1 year ago

Since Node is from launch_ros, have you tried updating ros-foxy-launch-ros?

Still NG. Btw actually I see launch-ros was not installed, as when I apt installed, it's getting as a new pkg.

Anyways, I still see it IS working when it started individually, but not via launch With `ros2 run` it works. ``` user:~/ros2_ws$ ros2 run ros1_bridge parameter_bridge __name:=parameter_bridge Trying to create bidirectional bridge for topic '/joint_states' with ROS 2 type 'sensor_msgs/msg/JointState' [INFO] [1682351493.831000121] [ros_bridge]: create bidirectional bridge for topic /joint_states Trying to create bidirectional bridge for topic '/clock' with ROS 2 type 'rosgraph_msgs/msg/Clock' [INFO] [1682351493.848145349] [ros_bridge]: create bidirectional bridge for topic /clock Trying to create bidirectional bridge for topic '/tf_static' with ROS 2 type 'tf2_msgs/msg/TFMessage' [INFO] [1682351493.868013067] [ros_bridge]: create bidirectional bridge for topic /tf_static [INFO] [1682351493.868081208] [ros_bridge]: Setting QoS to keep all msgs for topic /tf_static. Trying to create bidirectional bridge for topic '/tf' with ROS 2 type 'tf2_msgs/msg/TFMessage' [INFO] [1682351493.889457276] [ros_bridge]: create bidirectional bridge for topic /tf Trying to create bidirectional bridge for topic '/wrist_rgbd/depth/camera_info' with ROS 2 type 'sensor_msgs/msg/CameraInfo' [INFO] [1682351493.912990904] [ros_bridge]: create bidirectional bridge for topic /wrist_rgbd/depth/camera_info Trying to create bidirectional bridge for topic '/wrist_rgbd/depth/points' with ROS 2 type 'sensor_msgs/msg/PointCloud2' [INFO] [1682351493.939335367] [ros_bridge]: create bidirectional bridge for topic /wrist_rgbd/depth/points The parameter 'services_1_to_2' either doesn't exist or isn't an array The parameter 'services_2_to_1' either doesn't exist or isn't an array [INFO] [1682351494.003166739] [ros_bridge]: Passing message from ROS 1 rosgraph_msgs/Clock to ROS 2 rosgraph_msgs/msg/Clock (showing msg only once per type) [INFO] [1682351494.005927328] [ros_bridge]: Passing message from ROS 1 sensor_msgs/JointState to ROS 2 sensor_msgs/msg/JointState (showing msg only once per type) [INFO] [1682351494.108513580] [ros_bridge]: Passing message from ROS 1 tf2_msgs/TFMessage to ROS 2 tf2_msgs/msg/TFMessage (showing msg only once per type) [INFO] [1682351494.274043842] [ros_bridge]: Passing message from ROS 1 sensor_msgs/CameraInfo to ROS 2 sensor_msgs/msg/CameraInfo (showing msg only once per type) [INFO] [1682351494.294647887] [ros_bridge]: Passing message from ROS 1 sensor_msgs/PointCloud2 to ROS 2 sensor_msgs/msg/PointCloud2 (showing msg only once per type) ^C[INFO] [1682351500.538489992] [rclcpp]: signal_handler(signal_value=2) ``` With `ros2 launch` it's still no no. ``` user:~/ros2_ws$ ros2 launch foo_pkg start_bridge.launch.py [INFO] [launch]: All log files can be found below /home/user/.ros/log/2023-04-24-15-52-21-489212-2_xterm-15192 [INFO] [launch]: Default logging verbosity is set to INFO Task exception was never retrieved future: exception=InvalidLaunchFileError('py')> Traceback (most recent call last): File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/any_launch_file_utilities.py", line 53, in get_launch_description_from_any_launch_file return loader(launch_file_path) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/python_launch_file_utilities.py", line 62, in get_launch_description_from_python_launch_file launch_file_module = load_python_launch_file_as_module(python_launch_file_path) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/python_launch_file_utilities.py", line 37, in load_python_launch_file_as_module loader.exec_module(mod) File "", line 848, in exec_module File "", line 219, in _call_with_frames_removed File "/home/user/ros2_ws/install/foo_pkg/share/foo_pkg/config/start_bridge.launch.py", line 2, in from launch_ros.actions import Node File "/opt/ros/foxy/lib/python3.8/site-packages/launch_ros/__init__.py", line 17, in from . import actions File "/opt/ros/foxy/lib/python3.8/site-packages/launch_ros/actions/__init__.py", line 17, in from .composable_node_container import ComposableNodeContainer File "/opt/ros/foxy/lib/python3.8/site-packages/launch_ros/actions/composable_node_container.py", line 25, in from .node import Node File "/opt/ros/foxy/lib/python3.8/site-packages/launch_ros/actions/node.py", line 36, in from launch.frontend.type_utils import get_data_type_from_identifier ImportError: cannot import name 'get_data_type_from_identifier' from 'launch.frontend.type_utils' (/opt/ros/foxy/lib/python3.8/site-packages/launch/frontend/type_utils.py) The above exception was the direct cause of the following exception: Traceback (most recent call last): File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_service.py", line 228, in _process_one_event await self.__process_event(next_event) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_service.py", line 248, in __process_event visit_all_entities_and_collect_futures(entity, self.__context)) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 45, in visit_all_entities_and_collect_futures futures_to_return += visit_all_entities_and_collect_futures(sub_entity, context) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/utilities/visit_all_entities_and_collect_futures_impl.py", line 38, in visit_all_entities_and_collect_futures sub_entities = entity.visit(context) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/action.py", line 108, in visit return self.execute(context) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/actions/include_launch_description.py", line 125, in execute launch_description = self.__launch_description_source.get_launch_description(context) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_source.py", line 84, in get_launch_description self._get_launch_description(self.__expanded_location) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/any_launch_description_source.py", line 53, in _get_launch_description return get_launch_description_from_any_launch_file(location) File "/opt/ros/foxy/lib/python3.8/site-packages/launch/launch_description_sources/any_launch_file_utilities.py", line 56, in get_launch_description_from_any_launch_file raise InvalidLaunchFileError(extension, likely_errors=exceptions) launch.invalid_launch_file_error.InvalidLaunchFileError: Caught exception when trying to load file of format [py]: cannot import name 'get_data_type_from_identifier'from 'launch.front ```
$ apt-cache policy ros-foxy-launch-ros
ros-foxy-launch-ros:
  Installed: 0.11.7-1focal.20230317.010314
  Candidate: 0.11.7-1focal.20230317.010314
  Version table:
 *** 0.11.7-1focal.20230317.010314 500
        500 http://packages.ros.org/ros2/ubuntu focal/main amd64 Packages
        100 /var/lib/dpkg/status
christophebedard commented 1 year ago

Have you tried reproducing with Rolling? I tried to reproduce and I couldn't, so maybe it was fixed after Foxy. I also tried to find potential PRs that fixed this and I couldn't, but I might've just missed them.

130s commented 1 year ago

Sorry I made my post https://github.com/ros2/launch/issues/704#issuecomment-1520447328 here but it was actually about another problem.

I don't have a plan to use ROS Humble just yet :man_shrugging: so can't tell..

clalancette commented 1 year ago

So this is pretty subtle, but I think what is happening here is that the name that you are specifying in the launch file is being applied to all nodes inside of the executable. That is, both your move_group_node and your planner_node are being renamed to pick_place_sample2. Since we don't really support having two nodes with the same name, you get the behavior you see here.

I have at least two suggestions:

  1. For a quick fix, you can just get rid of the name argument to the Node call in the launch file. That will give the nodes their default names, and avoid the conflict.
  2. The real fix here is to restructure your code so you have one Node per library or executable. You can then compose them together using composable nodes, or something like that.