DDS configuration and rosbag
Hi there,
I have the following scenario:
- ROS Galactic RPi running a camera
- Laptop receiving images over the network
- Low bandwidth connection between RPi and Laptop
- Processing of the camera images happens on the laptop
- Recorded topics are being published from the laptop (post-processing from the raw camera output)
I have the above system working receiving and processing the camera images properly, but when I try to run rosbag to record the processed camera output (from the laptop), I see an increase in traffic sent back from the laptop to the RPi and the network saturates. This causes a loss of frames received from the RPi, being unable to properly record the rosbag.
I suspect that this has to do with the configuration of DDS and multicast over the low bandwith interface, but I'm not sure how to configure it. I did have a look at this other post, but with no luck, since I can't see the topics posted from the RPI anymore.
https://answers.ros.org/question/342191/how-to-disable-multicast-in-cyclone-dds/
Any suggestions? I have observed similar behavior using
ros2 topic hz topic_name
Asked by gecastro on 2022-09-22 20:46:57 UTC
Answers
I think that I did figure out the issue.
When there is only one subscriber, cyclone sends the traffic through the loopback interface, but if a second subscriber joins the topic it re-routes the traffic to the network interface. I assume that this behavior is to take advantage of multicast when a topic has multiple subscribers.
Since the re-routed data are uncompressed images, it causes serious bandwidth issues.
I did use this configuration to stop multicast in the network interface and I haven't seen the issue again.
<Domain id="any">
<General>
<NetworkInterfaceAddress>eth0</NetworkInterfaceAddress>
<AllowMulticast>spdp</AllowMulticast>
<EnableMulticastLoopback>true</EnableMulticastLoopback>
</General>
</Domain>
Asked by gecastro on 2022-10-24 23:00:21 UTC
Comments
How are you invoking rosbag to record the mentioned topics? Are you carefully specifying the topic filter to select only to record the topics published from the laptop, or are you leaving the topic names unspecified, which defaults to rosbag recording all topics from all publishers in the network.
https://github.com/ros2/rosbag2/blob/c2846e5ec6cdc0862f960949ba63e4566f1919e4/ros2bag/ros2bag/verb/record.py#L50-L55
Asked by ruffsl on 2022-09-23 11:00:11 UTC
I'm specifying only the topics that I want. The strange behavior is to see that the outgoing network traffic (from the laptop to the RPi) increases almost to the same traffic as the incoming images when I run rosbag in the laptop.
Asked by gecastro on 2022-09-28 02:39:43 UTC
Does this outgoing network traffic spike if you subscribe from-the-laptop to topics published by-the-laptop using anything other than rosbag, like ros2 topic echo, rviz, or rqt_topic? Just trying to rule out rosbag from the equation. Edit: NM, reread your note on ros2 topic hz. hmm...
Asked by ruffsl on 2022-09-29 07:30:18 UTC
This issue may be harder to reproduce in a separate environment, but would it be possible to replicate and post a minimal example using a pair of containers and check the docker runtime metrics for the same changes in network IO?
https://docs.docker.com/config/containers/runmetrics/
Not sure if using the host or macvlan network driver (that supports multicast to better replicate this issue's environment) still supports container specific telemetry on network io stats.
https://old.reddit.com/r/docker/comments/o8ywmx/multicast_in_a_container
Asked by ruffsl on 2022-09-29 07:48:46 UTC