Image streaming slowdown when using voxl-mpa-to-ros2
-
Hello,
I'm working with a Starling through a ground station computer to integrate it with an existing ROS system. I'd like to periodically read in a few of the video feeds. To do so, I've been running the voxl_mpa_to_ros2 node onboard the Starling. I wrote a short script (bottom of the post) to test it out, subscribing to the /tracking topic, then showing the image using CV2. I noticed that the video stream slowed down substantially on both my client computer AND the ModalAI portal (at 192.168.8.1), to only a few FPS, with substantial delay. I'm wondering if there's a workaround that I'm missing with this functionality. I'm connecting the ground station and the Starling through the SoftAP network/Starling-based network.
Thanks!
See responses to default questions below:
What hardware are you using? If you have specific SKU or serial number, that is also helpful
Starling
What version of software are you using? voxl-version is very helpful for determining software version.-------------------------------------------------------------------------------- system-image: 1.7.4-M0054-14.1a-perf kernel: #1 SMP PREEMPT Fri Feb 9 22:38:25 UTC 2024 4.19.125 -------------------------------------------------------------------------------- hw platform: M0054 mach.var: 1.2 -------------------------------------------------------------------------------- voxl-suite: 1.1.3-1 -------------------------------------------------------------------------------- Packages: Repo: http://voxl-packages.modalai.com/ ./dists/qrb5165/sdk-1.1/binary-arm64/ Last Updated: 2024-04-24 14:09:36 List: dpkg-query: no packages found matching onair_voxl libmodal-cv 0.4.0 libmodal-exposure 0.1.0 libmodal-journal 0.2.2 libmodal-json 0.4.3 libmodal-pipe 2.9.2 libqrb5165-io 0.4.2 qrb5165-bind 0.1-r0 qrb5165-dfs-server 0.2.0 qrb5165-imu-server 1.0.1 qrb5165-rangefinder-server 0.1.1 qrb5165-slpi-test-sig 01-r0 qrb5165-system-tweaks 0.2.6 qrb5165-tflite 2.8.0-2 --------------------------------------------------------------------------------
How have you configured the software? What is the output of voxl-inspect-services
Scanning services... Service Name | Enabled | Running | CPU Usage ------------------------------------------------------------------- docker-autorun | Disabled | Not Running | modallink-relink | Disabled | Not Running | voxl-camera-server | Enabled | Running | 43.5% voxl-cpu-monitor | Enabled | Running | 0.4% voxl-dfs-server | Disabled | Not Running | voxl-feature-tracker | Disabled | Not Running | voxl-flow-server | Disabled | Not Running | voxl-imu-server | Enabled | Running | 4.3% voxl-lepton-server | Disabled | Not Running | voxl-mavcam-manager | Enabled | Running | 0.0% voxl-mavlink-server | Enabled | Running | 2.5% voxl-microdds-agent | Enabled | Running | 5.2% voxl-modem | Disabled | Not Running | voxl-neopixel-manager | Disabled | Not Running | voxl-open-vins-server | Disabled | Not Running | voxl-portal | Enabled | Running | 2.4% voxl-px4-imu-server | Disabled | Not Running | voxl-px4 | Enabled | Running | 30.0% voxl-qvio-server | Enabled | Running | 17.6% voxl-rangefinder-server | Disabled | Not Running | voxl-remote-id | Disabled | Not Running | voxl-softap | Enabled | Completed | voxl-static-ip | Disabled | Not Running | voxl-streamer | Enabled | Running | 0.0% voxl-tag-detector | Disabled | Not Running | voxl-tflite-server | Disabled | Not Running | voxl-time-sync | Disabled | Not Running | voxl-uvc-server | Disabled | Not Running | voxl-vision-hub | Enabled | Running | 3.8% voxl-wait-for-fs | Enabled | Completed |
Do you have any logs? Uploading PX4 logs to https://logs.px4.io can be very helpful. See details on PX4 logs here
No
Have you looked at the source code? If so, can you point to any potential issues?And the code used to grab images from the topic:
import cv2 from cv_bridge import CvBridge from functools import partial import rclpy from rclpy.node import Node from sensor_msgs.msg import Image ROS_MSG_TYPE_MAPPINGS = { "Image": Image, } class ROSSubscriber(Node): def __init__(self, name, topic_definitions): super().__init__(node_name=name) self.sub_list = [] self.recv = {} self.br = CvBridge() for topic_definition in topic_definitions: message_type = ROS_MSG_TYPE_MAPPINGS[topic_definition['message_type']] self.sub_list.append(self.create_subscription( topic=topic_definition['topic'], msg_type=message_type, callback=partial(self.listener_callback, topic=topic_definition['topic']), qos_profile=10 )) def listener_callback(self, msg, topic): frame = self.br.imgmsg_to_cv2(msg) print(f'frame\n {frame}') cv2.imshow("camera", frame) cv2.waitKey(1) self.recv[topic] = msg def main(): rclpy.init() sub_node = ROSSubscriber(name='image_reader', topic_definitions=[{'topic': '/tracking', 'message_type': 'Image'}]) rclpy.spin(sub_node) rclpy.destroy_node(sub_node) rclpy.shutdown() if __name__ == '__main__': main()
-
@cfirth , can you try to test out the FPS (on VOXL2 and on your PC) using
rostopic hz
utility?Also, it seems in your python script you are printing the whole data frame to screen? that will certainly slow things down.
You can disable printing and showing the image and just print the current time (using
time.time()
) and check the time between the frames.Alex
-
I got ROS2 topic hz on the Starling and my ground station PC (using the ROS2 utility) - it maintains 30 FPS when run on the VOXL2, but drops significantly (around 20) when run on the PC. Also, the VOXL Web portal shows the camera "sending FPS" varying between 20 and 5 FPS. Using
ros2 topic echo
leads to a slightly less severe drop in FPS.I've tried running the script without the printouts and without showing the image, and get the same slowdown. I will do some research and see if it has to do with how I'm configuring my ROS2 subscribers but if
ros2 topic hz
slows it down I am not sure.Thank you for replying! I have a current workaround to grab a single image at a time (which is all I need for now) - I can create the subscriber node, spin it once to retrieve the image, and destroy the node while retaining the image data. Still, I'd like to have the ability to relay real time video through ROS2 in the future. Please let me know how else I can help!
-
@cfirth , if
rostopic hz
works at 30fps on voxl but drops to 20fps or lower on PC, then most likely your issue is the network connection. Try to do some network testing using standard tools likeinstall
iperf
on voxl2 and PC:apt-get install iperf
run on server:
voxl2:/$ iperf -s
run on client
iperf -c <server ip address>
You can let it run until it finishes (few seconds) or control-c the client, the stats will be printed.
-
@Alex-Kushleyev I've been using the VOXL's self-created Wifi - is it not intended for this kind of data transfer? I will try other networks. Thanks for all the help so far!
-
@cfirth , if you are streaming raw RGB images, then 6404803 is 921KB, at 30fps will be 27MB/s which is definitely more than you want to transfer over wifi for a single stream. You can measure the available bandwidth using iperf as i suggested in previous post. Consider using compressed image format in ROS or use h264/5 encoded streams. You can use voxl-streamer to encode the tracking frames into a streaming video. If you describe your use case in more detail, we can provide additional suggestions.
-
To echo @Alex-Kushleyev , ROS is a very inefficient way to view video. voxl-streamer with RTSP is much more efficient
-
@Alex-Kushleyev Great, I will look into transferring compressed images. Thanks for the guidance!