Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Slow CameraSensor update rate compared to GUI scene refresh rate #332

Open
zp-yang opened this issue Mar 15, 2023 · 11 comments
Open

Slow CameraSensor update rate compared to GUI scene refresh rate #332

zp-yang opened this issue Mar 15, 2023 · 11 comments
Assignees

Comments

@zp-yang
Copy link

zp-yang commented Mar 15, 2023

My problem

My application requires me to simulate at least 3 cameras to capture the scene and track a target's position. Each camera is set to 1920x1080 resolution at 30 fps in the .sdf file. However, when I run the simulation each camera can at most publish at 15 HZ (I am using ros-gz bridge and inspected the rate with ros2 topic hz). Even when I am only running one camera at this resolution it never reaches 30 fps and fluctuates around 23 HZ.

My setup

  • Ubuntu 22.04, gz-garden, and ros2-humble.
  • I have a rtx3080 gpu, ryzen 5800x cpu, and inspected the gz-gui's scene is running at 144 fps without a problem using mangohud.
  • I tried using headless rendering only on the server side but still getting the same low fps.
  • I tried remove everything in the scene except for the cameras, still same result.

My question

  • What is causing the discrepancy between the gui rendering and server rendering? I have check this tutorial RenderingPlugin but could not understand the issue.
  • Is there a way to potentially bring up the server side sensor's update rate to match what is seen in the gui scene?
  • How to inspect topic publish rate in gz-garden with gz topic

I would really appreciate if anyone can point me to a direction and I would love to help if you already started working on a fix.

@iche033
Copy link
Contributor

iche033 commented Mar 15, 2023

I think ros2 topic hz reports the rate in wall clock time and not sim time. So when the simulation is running slower than real time (with low RTF), you'll notice that the rate reported by ros2 is lower than the target update rate. Sometime ago I wrote a script that checks the timestamps of the ros2 camera msgs and verified that they are correct. So I think the cameras should be hitting the target rate but in "sim time". There are things put in place in gz to make sure simulation is slowed down if the cameras are not able to hit their target update rate.

What is causing the discrepancy between the gui rendering and server rendering?

gui rendering runs in a separate process from server and has its own thread for rendering. On the server side, all the rendering sensors perform updates in the same rendering thread. While some parallelizations are done on the GPU for the camera updates, there could still be other places where there is contention for resources, e.g. when reading data back from GPU to CPU, serializing and publishing the msgs.

Is there a way to potentially bring up the server side sensor's update rate to match what is seen in the gui scene?

I think we would need to profile where the performance bottleneck is first. In the past, getting data from GPU to CPU had been slow for us. That could be something to look into. But I'm not sure if there's a workaround that can be done on the user side unfortunately (apart from running without a gui which didn't seem to help in your case).

How to inspect topic publish rate in gz-garden with gz topic

I don't think that functionality is supported yet.

@zp-yang
Copy link
Author

zp-yang commented Mar 15, 2023

Thank you so much for these information!

I did more testing with the camera sensor purely in gz sim and found more "issues". If I do not use the ImageDisplay plugin to subscribe to one of the camera sensors, the real-time factor is almost 100% all the time. The moment I enable ImageDisplay and subscribe to one of the sensors, the RTF starts to fluctuate dramatically, between 50%- 90%. Similar issue happens when I echo the camera sensor with gz topic -e. I believe this is what happened when I use ros-gz bridge too. It seems like the subscription/publications is the bottleneck?

I also noticed that there is a --record and --playbackoption for gz sim. Is it recording all topics like a rosbag or just logging /state and /stats? Is it possible to record a simulation in gz and play it back at wall time so when I connect to the playback using ros-gz-bridge all the sensors would be updating at the correct rate?

@iche033
Copy link
Contributor

iche033 commented Mar 15, 2023

So in gazebo cameras do not actually update if there are no subscribers, hence the high RTF, i.e. no work is done because there are no consumers. It's only when you subscribe to the image topic e.g. through gz topic -e or ros_gz bridge, cameras start rendering and you get the fluctuations in RTF

As for the --record and --playback args, by default it works slightly different from rosbag. When you enable-record, it logs the clock topic, sdf data, and state (pose) of all objects to a database located in the path given by --record-path. You can then launch the sim in playback mode through --playback to replay the whole simulation. If you want more topics to be recorded, you'll need to specify them through the record-topic arg. I haven't tried running playback mode with the ros-gz-bridge before so not sure how well that works though.

@zp-yang
Copy link
Author

zp-yang commented Mar 16, 2023

Thanks! I did some primitive poking and have more question now.

  1. I checked the rending loop for RenderingSensor (I hope this is the right place) and it is updating at around 2000HZ for 4 cameras. So I am guessing the bottleneck is not on the renderer side. I will do more investigation on the pub/sub side.

  2. The camera_info_topic seems to be present in sdfomat13 and we should be able to set it for different cameras. However when I add this tag to the .sdf file I get a warning

XML Element[camera_info_topic], child of element[sensor], not defined in SDF. Copying[camera_info_topic] as children of [sensor].

So now all of the cameras are publishing their info to the default \camera_info topic. On the sdformat1.9 specification website there is also no mention of camera_info_topic.

@iche033
Copy link
Contributor

iche033 commented Mar 16, 2023

I checked the rending loop for RenderingSensor (I hope this is the right place) and it is updating at around 2000HZ for 4 cameras. So I am guessing the bottleneck is not on the renderer side. I will do more investigation on the pub/sub side.

Oh that loop measures the update rate for just 1 sensor (there is a for loop in there because some render sensors is made up of 2 sensors internally e.g. RGBD). If you want to measure the rendering thread's update rate for all rendering sensors, this is the place:
https://github.com/gazebosim/gz-sim/blob/gz-sim7/src/systems/sensors/Sensors.cc#L388

The camera_info_topic seems to be present in sdfomat13 and we should be able to set it for different cameras. However when I add this tag to the .sdf file I get a warning

Hmm that was added recently but the doc hasn't been updated yet. To fix the issue, <camera_info_topic> should be inside <camera>, e.g.

<sensor ..>
  <camera ..>
    <camera_info_topic>my_topic</camera_info_topic>

You'll also need make sure your sdformat 13 version is >= 13.4.1 as there was a recent patch to fix the camera_topic_info default value

@zp-yang
Copy link
Author

zp-yang commented Mar 16, 2023

Ah I see, the actual render loop is giving me around 12 HZ when 4 cameras are subscribed, which is consistent with the real time update rate.

@zp-yang
Copy link
Author

zp-yang commented Mar 20, 2023

I timed each stage in the camera sensor's update process and found that there is a dramatic slow down from the sensor update loop to the manager update loop. Hope this is helpful and I will keep digging.

[Dbg] [CameraSensor.cc:582] Render frequency camera_0::link::camera_0 | 173.334 HZ
[Dbg] [CameraSensor.cc:656] Sensor Pub rate camera_0::link::camera_0 | 112.024 HZ
[Dbg] [CameraSensor.cc:582] Render frequency camera_1::link::camera_1 | 158.845 HZ
[Dbg] [CameraSensor.cc:656] Sensor Pub rate camera_1::link::camera_1 | 108.384 HZ
[Dbg] [CameraSensor.cc:582] Render frequency camera_2::link::camera_2 | 150.783 HZ
[Dbg] [CameraSensor.cc:656] Sensor Pub rate camera_2::link::camera_2 | 104.669 HZ
[Dbg] [CameraSensor.cc:582] Render frequency camera_3::link::camera_3 | 151.266 HZ
[Dbg] [CameraSensor.cc:656] Sensor Pub rate camera_3::link::camera_3 | 103.975 HZ
[Dbg] [Manager.cc:86] manager update loop update rate 26.722 HZ
[Dbg] [Sensors.cc:402] RenderThread update rate 14.4941 HZ

Edit: The Manager Loop rate makes sense because each camera is publishing at 100hz and there are 4 of them so the loop should be 100/4 = 25hz. The issue is within the render and copy step I think.

@zp-yang
Copy link
Author

zp-yang commented Mar 20, 2023

similar issue in ros-gz #368

@zp-yang
Copy link
Author

zp-yang commented Mar 21, 2023

I started testing with only one camera this time, the first slow down is at copying data from GPU, then preparing image data for publishing, and lastly in the RenderThread.

[Dbg] [CameraSensor.cc:580] Render frequency camera_0::link::camera_0 | 2981.33 HZ
[Dbg] [CameraSensor.cc:589] Copy rendered image frequency camera_0::link::camera_0 | 156.601 HZ
[Dbg] [CameraSensor.cc:665] Sensor Pub rate camera_0::link::camera_0 | 97.7739 HZ
[Dbg] [Manager.cc:86] manager update loop update rate 97.4804 HZ
[Dbg] [Sensors.cc:402] RenderThread update rate 24.0892 HZ
[Dbg] [CameraSensor.cc:580] Render frequency camera_0::link::camera_0 | 1845.59 HZ
[Dbg] [CameraSensor.cc:589] Copy rendered image frequency camera_0::link::camera_0 | 152.35 HZ
[Dbg] [CameraSensor.cc:665] Sensor Pub rate camera_0::link::camera_0 | 93.1231 HZ
[Dbg] [Manager.cc:86] manager update loop update rate 92.8552 HZ
[Dbg] [Sensors.cc:402] RenderThread update rate 23.7734 HZ

@iche033
Copy link
Contributor

iche033 commented Mar 21, 2023

I timed each stage in the camera sensor's update process and found that there is a dramatic slow down from the sensor update loop to the manager update loop. Hope this is helpful and I will keep digging.

thanks for the profiling the update loops! I do expect there are differences but it's larger than I thought. This led me to investigate what's causing the differences and made some slight optmizations in gazebosim/gz-sim#1938. If you have time, feel free to try out the branch and see if it helps your use case.

@zp-yang
Copy link
Author

zp-yang commented Mar 21, 2023

Thank you so much for this fix. I just tested this branch and the performance improvement is great for a single camera sensor. ROS reported update rate matches the target (both at 30hz). For the 4-camera scenario the RenderThread is reporting 15 hz, instead of 12hz from before. For my usage I could just run 4 different simulations with only one camera enable each time and get somewhat realtime data after combining them.

By the way do you know how dataPtr->camera->Copy() is implemented? I might've missed something in gz-rendering while exploring it. Edit: nvm found it.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Status: In progress
Development

No branches or pull requests

2 participants