launch_ros
launch_ros copied to clipboard
Component Containers on Different ROS_DOMAIN_IDs Fail to Launch
Bug report
In my application I simulate multiple agents, each in their own domain. I'm trying to move my nodes over to be components, but am running into challenges within my launch files. When the domain ID is specified as an additional_env
, only the first container loads, and any other containers fail to load their components. It seems that the service callback in load_composable_nodes.py
gets stuck.
The below example works if you:
- Remove
additional_env
arguments. - Run each container in their own launch file and run from their own
ros2 launch
command. - Change the
ROS_DOMAIN_ID
to be the same.
Required Info:
- Operating System: Ubuntu 22.04, humble and rolling
- Installation type: Binaries
- Version or commit hash: Rolling/humble docker image pulled on 2 FEB 2023
- DDS implementation: Fast-DDS
- Client library (if applicable): N/A
Steps to reproduce issue
#!/usr/bin/env python3
from launch import LaunchDescription
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
return LaunchDescription([
ComposableNodeContainer(
package='rclcpp_components',
executable='component_container',
name='container1',
namespace='ns1',
additional_env={
'ROS_DOMAIN_ID': '1',
},
composable_node_descriptions=[
ComposableNode(
package='robot_state_publisher',
plugin='robot_state_publisher::RobotStatePublisher',
name='robot_state_publisher',
namespace='ns1',
parameters=[
{'robot_description': '<robot name="robot"><link name="imu" /></robot>'},
]
),
]
),
ComposableNodeContainer(
package='rclcpp_components',
executable='component_container',
name='container2',
namespace='ns2',
additional_env={
'ROS_DOMAIN_ID': '2',
},
composable_node_descriptions=[
ComposableNode(
package='robot_state_publisher',
plugin='robot_state_publisher::RobotStatePublisher',
name='robot_state_publisher',
namespace='ns2',
parameters=[
{'robot_description': '<robot name="robot"><link name="imu" /></robot>'},
]
),
]
)
])
Expected behavior
robot state publisher loads in both containers
Actual behavior
robot state publisher loads in only one of the containers
Additional information
If there are alternative ways of doing this, I'm open to that as well.
I agree that this is likely an oversight in the way that ComposableNodeContainer and ComposableNode interact. In this case, I would expect that the domain ID is propagated correctly.
Under the hood, the ComposableNode
description ends up making a service call against the ComposableNodeContainer
. When the service client and server end up on different domains, then the failure occurs.
I will work on a fix.