ros2 / rclpy

rclpy (ROS Client Library for Python)
Apache License 2.0
303 stars 225 forks source link

Publish rate decreasing rapidly during republish of an image type sensor_msg/Image #630

Open ashwinsushil opened 4 years ago

ashwinsushil commented 4 years ago

Bug report

Required Info:

Steps to reproduce issue

I have created a docker file to reproduce the issue.

Please pull the docker image:

docker pull ashwinsushil/image-republish-issue:v1.0

Start the container in interactive mode by

docker run --rm -it --net host ashwinsushil/image-republish-issue:v1.0 /bin/bash

Once inside the container, source the script:

source /ros2_dev_entrypoint.sh 

Run the node that republishes the image (please ignore the naming):

ros2 run detection_visualizer detection_visualizer &

Check the rate of republished image (at the moment it is publishing an empty message type Image)

ros2 topic hz /republished_images

In another terminal inside the docker, run the image publisher that publishes an ROS2 image topic from the video named v4.mp4

ros2 run image_publisher image_publisher_node v4.mp4 --ros-args -p publish_rate:=30. -r image_raw:=/source_images &

Expected behavior

/republished_images topic publishes at 30hz at all times.

Actual behavior

/republished_images topic publishing decrease from 30hz to 5hz when the /source_images is fed from the ros-foxy-image-publisher

Additional information

I tried using FastRTPS and CycloneDDS implementation of the ros2 middleware but the behaviour is the same.

The code is already inside the docker image inside /umd2_ws

import rclpy
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
from sensor_msgs.msg import Image

class DetectionVisualizerNode(Node):

    def __init__(self):
        super().__init__('detection_visualizer')

        self.received_msg_ = Image()

        output_image_qos = QoSProfile(
            history=QoSHistoryPolicy.KEEP_LAST,
            durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
            reliability=QoSReliabilityPolicy.RELIABLE,
            depth=1)

        timer_period = 0.03  # seconds
        self.timer = self.create_timer(timer_period, self.timer_callback)

        self._image_pub = self.create_publisher(Image, 'republished_images', output_image_qos)

        self._image_sub = self.create_subscription(Image, 'source_images',
                                                   self.image_callback, 10)

    # subsriber callback to the image from ros-foxy-image-publisher
    def image_callback(self, received_image):
        self.received_msg_ = received_image

    # republishing the image
    def timer_callback(self):
        self._image_pub.publish(self.received_msg_)

def main():
    rclpy.init()
    rclpy.spin(DetectionVisualizerNode())
    rclpy.shutdown()
ivanpauno commented 4 years ago

When I start the node, the /republished_images topic publishes at 30hz (as given in the publisher) but the moment I start ros-foxy-image-publisher and the /source_images is fed in the node, the rate of /republished_images decreasing rapidly from 30hz to 27hz to 25 to 20hz and finally settles at 5hz.

How are you measuring the rate? are you using ros2 topic hz?

AFAIR, that uses a best effort subscription. Maybe that's the issue. What is the size of the images being published?

ashwinsushil commented 3 years ago

Sorry for the late reply @ivanpauno. Yes, I'm using ros2 topic hz to measure the rate. FYI, when I use ros2 topic hz /source_image the rate is constant 30Hz. However, it is on /republished_images that the topic rate is low.

By the size did you mean the height and width? Then the height is 1080 and the width is 1920.

I modified the code to reduce the size of the image by 20% and now I can republish the image at 30hz. However, the quality is bad. But I don't still understand why I am unable to republish the image with original size.

Modified callback,

    def image_callback(self, received_image):
        cv_image = self._bridge.imgmsg_to_cv2(received_image)
        scale_percent = 20 # percent of original size
        width = int(cv_image.shape[1] * scale_percent / 100)
        height = int(cv_image.shape[0] * scale_percent / 100)
        dim = (width, height)
        resized = cv2.resize(cv_image, dim, interpolation = cv2.INTER_AREA)

        self.received_msg_ = self._bridge.cv2_to_imgmsg(resized, encoding="bgr8")
ivanpauno commented 3 years ago

@ashwinsushil Sorry for the super-late reply.

By the size did you mean the height and width? Then the height is 1080 and the width is 1920.

I actually want to know the size in "MB" of the images (if your image was RGB24 the size would be ~3.4MB).

Some of the DDS implementations don't work pretty well out of the box with large messages (particularly if not all the QoS profiles are well tuned). See https://index.ros.org/doc/ros2/Troubleshooting/DDS-tuning/.

Your depth=1 option in the publisher also looks suspicious, maybe you're overriding the history cache before the last image went to the wire. Can you try depth=10 or higher?

It would also be good if you can measure how often the timer_callback is being triggered in your code (i.e. if the timer is actually being triggered at 30Hz). If it's not being triggered at that rate, this is likely a rclpy performance problem. If not, this is more likely a not good QoS profile or DDS-tunning issue.