Open vik748 opened 6 months ago
A simple thing like image publishing should work out of the box. Am I missing something?
There are likely 2 things going on here; slowness in rclpy for publishing, and slowness of ros2 topic hz
.
For the first one, you can try running with Python optimizations enabled:
python3 -O test_image_publisher.py
(this has been fixed in newer versions of ROS 2 automatically)
For the second one, I would try measuring the rate using another tool for now, preferably one written in C++.
Also, it might be helpful to try the whole thing in C++, as it is far more performant than Python at the moment.
@clalancette given that by using cyclone with the specified settings, this issue goes away. I highly doubt that this is related to python. But for completeness I will try this with cpp too.
FYI @MiguelCompany and @EduPonz.
@vik748
With Cyclone DDS I see a similar issue out of the box, but I can fix it by setting:
sudo sysctl -w net.core.rmem_max=2147483647
If setting the socket buffer sizes solves the issue with Cyclone DDS, I would try the same thing with Fast DDS.
You could also set the requested buffer sizes in the XML configuration of Fast DDS as explained here
@clalancette @MiguelCompany here are something things I have tested:
ros2 topic hz
.ros2 topic hz
which results in the difference. So when I changed my C++ subscriber to use rmw_qos_profile_sensor_data
, I do observe rate drop similar to that from ros2 topic hz
.@MiguelCompany in the link you provided, it says:
In high rate scenarios or large data scenarios, network packages can be dropped because the transmitted amount of data fills the socket buffer before it can be processed. Using RELIABLE_RELIABILITY_QOS mode, Fast DDS will try to recover lost samples, but with the penalty of retransmission. With BEST_EFFORT_RELIABILITY_QOS mode, samples will be definitely lost.
This lines up with what I am observing, however increasing the socket buffer sizes both the read and the write socket, doesn't to solve the issue. I have tried increasing it with with the sysctl
commands and with the XML file, but no luck. Have you been able to reproduce on your setup with the code I have above.
I am experiencing the same issue on Ubuntu 24 + Jazzy. Raw images from usb cam are received (by, e.g., rqt_image_view
around 2 Hz, whereas compressed theora runs at 30 Hz.
Bug report
Required Info:
Steps to reproduce issue
I noticed the issue when using the official Intel Realsense ROS drivers, but it can be reproduced with this simple minimal example.
Test with:
Expected behavior
The subscriber should receive images at 15hz.
Actual behavior
As seen above the images start at 4hz and drop down to almost 1hz on my 13th Gen Intel i7 laptop.
With Cyclone DDS I see a similar issue out of the box, but I can fix it by setting:
sudo sysctl -w net.core.rmem_max=2147483647
None of the suggested settings from https://docs.ros.org/en/humble/How-To-Guides/DDS-tuning.html helped address this.
Additional information
A simple thing like image publishing should work out of the box. Am I missing something?