You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have a ROS2 node that transmits RGB images weighing about 15 MB at a rate of 2 frames per second. When connecting a subscriber node from another PC, I expect to see a network transmission/reception rate of 30 MB/s due to the image size and frame rate.
Upon monitoring the network bandwidth using slurm, I noticed that the network bandwidth used is about 57 MB/s instead of the expected 30 MB/s.
Here is the source code for the publisher:
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "std_msgs/msg/header.hpp"
#include <chrono>
#include <cv_bridge/cv_bridge.h> // cv_bridge converts between ROS 2 image messages and OpenCV image representations.
#include <image_transport/image_transport.hpp> // Using image_transport allows us to publish and subscribe to compressed image streams in ROS2
#include <opencv2/opencv.hpp> // We include everything about OpenCV as we don't care much about compilation time at the moment.
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/core/core.hpp>
using namespace std::chrono_literals;
using namespace std;
using namespace cv;
class camera_macro_publisher : public rclcpp::Node {
public:
camera_macro_publisher() : Node("image_macro_publisher"), count_(0) {
publisher_ =
this->create_publisher<sensor_msgs::msg::Image>("camera_macro_publisher", 1);
timer_ = this->create_wall_timer(
500ms, std::bind(&camera_macro_publisher::timer_callback, this));
}
private:
void timer_callback() {
// Create a new 2592x1944 image
cv::Mat my_image(cv::Size(2592, 1944), CV_8UC3);
// Generate an image where each pixel is a random color
cv::randu(my_image, cv::Scalar(0, 0, 0), cv::Scalar(255, 255, 255));
// Declare the text position
cv::Point text_position(15, 40);
// Declare the size and color of the font
int font_size = 1;
cv::Scalar font_color(255, 255, 255);
// Declare the font weight
int font_weight = 2;
// Put the text in the image
cv::putText(my_image, "ROS2 + OpenCV, Image macro published: " + std::to_string(count_), text_position, cv::FONT_HERSHEY_COMPLEX, font_size, font_color, font_weight);
//std::string windowName = "Camera Image";
//cv::imshow(windowName, my_image);
//cv::waitKey(0);
//int key = waitKey(1000); //1 seconds
// Write message to be sent. Member function toImageMsg() converts a CvImage
// into a ROS image message
msg_ = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", my_image).toImageMsg();
// Publish the image to the topic defined in the publisher
publisher_->publish(*msg_.get());
RCLCPP_INFO(this->get_logger(), "Image %ld published", count_);
count_++;
if (count_ == 10) count_ = 0;
}
rclcpp::TimerBase::SharedPtr timer_;
sensor_msgs::msg::Image::SharedPtr msg_;
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
size_t count_;
};
int main(int argc, char *argv[]) {
rclcpp::init(argc, argv);
// create a ros2 node
auto node = std::make_shared<camera_macro_publisher>();
// process ros2 callbacks until receiving a SIGINT (ctrl-c)
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
The network bandwidth consumption should be consistent with the expected rate of 30 MB/s when transmitting images at 2 fps, both when directly subscribing to the topic and when using ROS2 diagnostic tools.
Actual behavior
The network bandwidth consumption is of about 57 MB/s. When using ros2 topic echo, I observe the same high network consumption of 57 MB/s. However, when I use ros2 topic bw or ros2 topic hz, the network consumption drops to the expected 30 MB/s.
Additional information
Due to the large message size, I have performed some basic DDS tuning on both the publisher and subscriber, setting:
interesting. are you looking that the network usage on specific PID, in this case process ID for publisher and subscriber? and baseline usage (nodes are discovered, but endpoint communication is not started yet.) is almost zero?
When using ros2 topic echo, I observe the same high network consumption of 57 MB/s. However, when I use ros2 topic bw or ros2 topic hz, the network consumption drops to the expected 30 MB/s.
this does not ring a bell for me. ros2 topic echo and bw/hz, both creates the subscription. QoS can be different but i would not expect this difference almost doubled...
Bug report
Required Info:
Steps to reproduce issue
I have a ROS2 node that transmits RGB images weighing about 15 MB at a rate of 2 frames per second. When connecting a subscriber node from another PC, I expect to see a network transmission/reception rate of 30 MB/s due to the image size and frame rate.
Upon monitoring the network bandwidth using slurm, I noticed that the network bandwidth used is about 57 MB/s instead of the expected 30 MB/s.
Here is the source code for the publisher:
And here is the source code for the subscriber:
Expected behavior
The network bandwidth consumption should be consistent with the expected rate of 30 MB/s when transmitting images at 2 fps, both when directly subscribing to the topic and when using ROS2 diagnostic tools.
Actual behavior
The network bandwidth consumption is of about 57 MB/s. When using ros2 topic echo, I observe the same high network consumption of 57 MB/s. However, when I use ros2 topic bw or ros2 topic hz, the network consumption drops to the expected 30 MB/s.
Additional information
Due to the large message size, I have performed some basic DDS tuning on both the publisher and subscriber, setting:
The text was updated successfully, but these errors were encountered: