Open jaan1729 opened 5 days ago
@jaan1729 this appears to be a timing issue, the replay launch file which are currently implemented in xml format can't use the more proper event based activation. So it currently configures and activates the pcap replay node after a fixed time has passed, which seems to be insufficient when using CycloneDDS, I think the easiest workaround probably to increase the sleep period on the two following execute commands within the pcap_replay.launch.xml
:
<!-- HACK: configure and activate the replay node via a process execute since state
transition is currently not availabe through launch.xml format -->
<executable if="$(var _use_metadata_file)"
cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_pcap configure"
launch-prefix="bash -c 'sleep 0; $0 $@'" output="screen"/>
<executable if="$(var _use_metadata_file)"
cmd="$(find-exec ros2) lifecycle set /$(var ouster_ns)/os_pcap activate"
launch-prefix="bash -c 'sleep 1; $0 $@'" output="screen"/>
This is a workaround to get you going, ultimately a better solution would be to port these launch files to the python format or implement the "auto_start" flag similar to the sensor/driver nodes.
Hope this helps!
I tried increasing the sleep duration in the launch file (up to 20 seconds) but no success.
I commented out the lifecycle commands within the launch file and re-ran it. This resulted in the following log message
Despite the launch file apparently functioning with commented-out lifecycle commands, I can't find /ouster/os_pcap
node from both ros2 lifecycle nodes
and ros2 node list
commands. Both the launch file and the current environment are configured with the same RMW implementation (rmw_cyclonedds_cpp)
Interestingly, I can find the node with the same steps when using the default DDS implementation.
I can't re-produce the same behavior on my machine after commenting out the block above. The /ouster/os_pcap
does show up in both lists (I use CycloneDDS on Ubuntu 22.04 running Humble). Maybe consider applying the latest updates on your system and see if that helps.
Describe the bug The ouster_pcap node is not working with CycloneDDS. However, it works fine when the DDS is set to default.
To Reproduce Steps to reproduce the behavior:
Setting the DDS:
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
compile the project workspace:
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release -DBUILD_PCAP=ON --packages-select ouster_sensor_msgs ouster_ros
ros launch ouster_ros sensor or replay:
ros2 launch ouster_ros replay_pcap.launch.xml pcap_file:=/workspace/pcaps/2024099_1400_OS-1-128_122421001099.pcap metadata:=/workspace/pcaps/2024099_1400_OS-1-128_122421001099.json
The Issue
Setting default DDS:
export RMW_IMPLEMENTATION=''
ros launch ouster_ros sensor or replay:
ros2 launch ouster_ros replay_pcap.launch.xml pcap_file:=/root/ros2_bags/pcaps/2024099_1400_OS-1-128_122421001099.pcap metadata:=/root/ros2_bags/pcaps/2024099_1400_OS-1-128_122421001099.json
Working successfully:
Platform (please complete the following information):