Error
Run planning sim demo in ROS 2 Jazzy.
[component_container_mt-16] 1769256670.700802 [0] component_: Failed to find a free participant index for domain 0
[component_container_mt-16] [ERROR 1769256670.700870533] [rmw_cyclonedds_cpp]: rmw_create_node: failed to create domain, error Error (check_create_domain() at ./src/rmw_node.cpp:1242)
[component_container_mt-16] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[component_container_mt-16] what(): failed to initialize rcl node: error not set, at ./src/rcl/node.c:252
[component_container_mt-36] 1769256670.709949 [0] component_: Failed to find a free participant index for domain 0
[component_container_mt-36] [ERROR 1769256670.710007886] [rmw_cyclonedds_cpp]: rmw_create_node: failed to create domain, error Error (check_create_domain() at ./src/rmw_node.cpp:1242)
[component_container_mt-36] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
System
- Ubuntu 24.04
- ROS 2 Jazzy
RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
CYCLONEDDS_URI=file:///home/mfc/cyclonedds.xml
cyclonedds.xml file
<?xml version="1.0" encoding="UTF-8" ?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain Id="any">
<General>
<Interfaces>
<NetworkInterface name="lo" priority="default" multicast="default"/>
</Interfaces>
<AllowMulticast>default</AllowMulticast>
<MaxMessageSize>65500B</MaxMessageSize>
</General>
<Internal>
<SocketReceiveBufferSize min="10MB"/>
<Watermarks>
<WhcHigh>500kB</WhcHigh>
</Watermarks>
</Internal>
<Tracing>
<Verbosity>config</Verbosity>
<OutputFile>/home/mfc/dds_logs/cdds.log.${CYCLONEDDS_PID}</OutputFile>
</Tracing>
</Domain>
</CycloneDDS>
multicast status
Enabled:
mfc@whale:~$ ifconfig lo
lo: flags=4169<UP,LOOPBACK,RUNNING,MULTICAST> mtu 65536
inet 127.0.0.1 netmask 255.0.0.0
inet6 ::1 prefixlen 128 scopeid 0x10<host>
loop txqueuelen 1000 (Local Loopback)
RX packets 8415231 bytes 3311458942 (3.3 GB)
RX errors 0 dropped 0 overruns 0 frame 0
TX packets 8415231 bytes 3311458942 (3.3 GB)
TX errors 0 dropped 0 overruns 0 carrier 0 collisions 0
How to fix?
Add:
<Discovery>
<ParticipantIndex>auto</ParticipantIndex>
<MaxAutoParticipantIndex>1000</MaxAutoParticipantIndex>
</Discovery>
Full cyclonedds.xml file:
<?xml version="1.0" encoding="UTF-8" ?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain Id="any">
<Discovery>
<ParticipantIndex>auto</ParticipantIndex>
<MaxAutoParticipantIndex>1000</MaxAutoParticipantIndex>
</Discovery>
<General>
<Interfaces>
<NetworkInterface name="lo" priority="default" multicast="default"/>
</Interfaces>
<AllowMulticast>default</AllowMulticast>
<MaxMessageSize>65500B</MaxMessageSize>
</General>
<Internal>
<SocketReceiveBufferSize min="10MB"/>
<Watermarks>
<WhcHigh>500kB</WhcHigh>
</Watermarks>
</Internal>
<Tracing>
<Verbosity>config</Verbosity>
<OutputFile>/home/mfc/dds_logs/cdds.log.${CYCLONEDDS_PID}</OutputFile>
</Tracing>
</Domain>
</CycloneDDS>
References
https://cyclonedds.io/docs/cyclonedds/0.9.1/config.html#controlling-port-numbers
When it is auto, Eclipse Cyclone DDS probes UDP port numbers on start-up, starting with PI = 0, incrementing it by one each time until it finds a pair of available port numbers, or it hits the limit. The maximum PI it will ever choose is Discovery/MaxAutoParticipantIndex as a way of limiting the cost of unicast discovery.
https://docs.picknik.ai/how_to/computer_configuration/customize_dds_configuration/#1-default-let-moveit-pro-configure-a-single-computer-cyclone-dds-configuration
https://cyclonedds.io/docs/cyclonedds/latest/config/config_file_reference.html#cyclonedds-domain-discovery-maxautoparticipantindex
//CycloneDDS/Domain/Discovery/MaxAutoParticipantIndex
Integer
This element specifies the maximum DDSI participant index selected by this instance of the Cyclone DDS service if the Discovery/ParticipantIndex is "auto". This also determines the range of port numbers pinged by default for unicast participant discovery.
The default value is: 99
(But true default in jazzy is even lesser than 50 or something empirically, not sure what it is)
How to get DDS participant count when a launch file is run?
- Terminate all ros2 nodes
rm /home/mfc/dds_logs/* # this is set by <OutputFile>/home/mfc/dds_logs/cdds.log.${CYCLONEDDS_PID}</OutputFile> in cyclonedds.xml file
watch -n 0.2 "ls /home/mfc/dds_logs | wc -l"
In another terminal, run ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/home/mfc/autoware_map/sample-map-planning vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit with your map path.
The count will be 50 if everything goes to plan.
mfc@whale:~$ ros2 topic list | wc -l
595
mfc@whale:~$ ros2 node list | wc -l
138
The discrepancy between node count and dds participants come from probably ROS 2 Composable Node Containers.
mfc@whale:~$ ros2 component list | wc -l
85
mfc@whale:~$ ros2 component list | grep -E '^\s+[0-9]+' | wc -l
70
138-85=53 not sure how 3 is accounted for lol.
Task
Error
Run planning sim demo in ROS 2 Jazzy.
System
RMW_IMPLEMENTATION=rmw_cyclonedds_cppCYCLONEDDS_URI=file:///home/mfc/cyclonedds.xmlcyclonedds.xmlfilemulticast status
Enabled:
How to fix?
Add:
Full cyclonedds.xml file:
References
https://cyclonedds.io/docs/cyclonedds/0.9.1/config.html#controlling-port-numbers
https://docs.picknik.ai/how_to/computer_configuration/customize_dds_configuration/#1-default-let-moveit-pro-configure-a-single-computer-cyclone-dds-configuration
https://cyclonedds.io/docs/cyclonedds/latest/config/config_file_reference.html#cyclonedds-domain-discovery-maxautoparticipantindex
(But true default in jazzy is even lesser than 50 or something empirically, not sure what it is)
How to get DDS participant count when a launch file is run?
In another terminal, run
ros2 launch autoware_launch planning_simulator.launch.xml map_path:=/home/mfc/autoware_map/sample-map-planning vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kitwith your map path.The count will be
50if everything goes to plan.The discrepancy between node count and dds participants come from probably ROS 2 Composable Node Containers.
138-85=53not sure how 3 is accounted for lol.Task