ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Ros image message rate is low.

asked 2018-07-09 04:24:35 -0500

RomanShametko gravatar image

updated 2018-07-15 07:04:36 -0500

I'm trying to get VREP vision sensor output processed with opencv via ROS api. I did manage to set up scene and get scripts running, but the problem is that I get somewhat like 4-5 fps even without actual processing (currently I just push images directly to output).

This issue does not seem to depend on image resolution, since both 1024512 and 128128 captures result in exactly the same fps.

This also is not a matter of blocking calls, although I'm posting single-theaded code, I do have quite complex multithreaded processing pipeline which performs rather well with actual cameras (~50 fps).

Lua scripts on VREP's side do not seem to be a problem also, since I've tried to play with video retranslation examples provided by vrep, and they seem to achieve rather satisfying fps.

So it seems like image streaming is a bottleneck.

Here's my sample script:

# coding=utf-8

import rclpy
import rclpy.node as node
import cv2
import numpy as np
import sensor_msgs.msg as msg

import third_party.ros.ros as ros

class TestDisplayNode(node.Node):
    def __init__(self):
        super().__init__('IProc_TestDisplayNode')
        self.__window_name = "img"
        self.sub = self.create_subscription(msg.Image, 'Vision_sensor', self.msg_callback)

    def msg_callback(self, m : msg.Image):
        np_img = np.reshape(m.data, (m.height, m.width, 3)).astype(np.uint8)
        self.display(np_img)

    def display(self, img : np.ndarray):
        cv2.imshow(self.__window_name, cv2.cvtColor(img, cv2.COLOR_RGB2BGR))
        cv2.waitKey(1)

def main():
    ros_core = ros.RclpyWrapper()

    node = TestDisplayNode()

    rclpy.spin(node)

    node.destroy_node()
    rclpy.shutdown()

if __name__ == "__main__":
    main()

I also have to mention that I run it with ros bridge, since I need processing done with python3, which is supported by ROS2 only, and VREP seems to work only with ROS1 (although I'm just starting to work with these systems, so I'm not confident in that case).

UPDATE:

It seems like I have bee mistaken a bit about ros bandwidth capabilities. Frame rate actually changes with frame resolution.

But what actually puzzles me is how it is actually supposed to work? The best result I could get is 6464 video with decent frame rate. Even two 6464 sensors result in lower frame rate. How machine vision dependent projects are supposed to be done in with ROS?

I was actually hoping to use simulation with ROS since it could provide a lot of background and simplify testing and evaluation. Although I have not try to use gazebo yet.

Any advice is welcome.

Copying some comments, since I need to remove my update, which was originally created as an answer post.

@William : I haven't tried sending images with rclpy -> rclpy , but our image demos in C++ perform a lot better than that on most machines. Maybe as a base line you could try one of our image demos to see if the issue exists there too: https://github.com/ros2/ros2/wiki/Qua...

@William : Good performance with images (even large ones) is definitely possible with ROS 1 ... (more)

edit retag flag offensive close merge delete

Comments

There are a lot of moving pieces here, with VREP/ROS 1 and the ros1_bridge and rclpy. It's unlikely anyone will have time to reproduce your entire pipeline and then profile it for you to find the issue. I'd recommend trying to narrow down which part is slow and make a simpler example from that.

William gravatar image William  ( 2018-07-09 17:35:17 -0500 )edit

What version of ROS 2 are you using? I'd recommend using the Bouncy release or building ROS 2 from source using the latest "master".

William gravatar image William  ( 2018-07-16 19:23:36 -0500 )edit

I'm using latest distro (the one I found here https://github.com/ros2/ros2/wiki/Lin... ). Actually, there's a bug created on github ( https://github.com/ros2/ros2/issues/509 ). Currently I have MWE posted there, and I also plan to get some profiling done by today night.

RomanShametko gravatar image RomanShametko  ( 2018-07-17 02:03:39 -0500 )edit
1

Following up here as well: One main difference between the C++ and Python messages is that in Python we enforce the validity of the data set in the message fields at runtime. To skip the checking of data validity you can set PYTHONOPTIMIZE=0 in your environment. Performance should be much better

marguedas gravatar image marguedas  ( 2018-07-30 19:18:56 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-08-02 16:50:48 -0500

RomanShametko gravatar image

After some research we've found out that there are huge performance loss inside message conversion function in rclpy (see ling to issue on github in comments to original question for details).

As a workaround, you might run python with -O option, which disables a lot of asserts. That results in decent frame rate growth.

@marguedas also suggested setting PYTHONOPTIMIZE=0. Although I did not try it yet, I assume it will lead to the same result.

edit flag offensive delete link more

Comments

Yes, PYTHONOPTIMIZE=0 or passing -O should have the same effect.

For the curious, there is another discussion on how to optimize these functions even further at https://github.com/ros2/rosidl_python...

marguedas gravatar image marguedas  ( 2018-08-02 19:07:10 -0500 )edit

More about the PYTHONOPTIMIZE can be found here https://ziade.org/2015/11/25/should-i...

Merwan gravatar image Merwan  ( 2020-10-16 23:54:47 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-07-09 04:24:35 -0500

Seen: 2,310 times

Last updated: Aug 02 '18