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

Performance issues with bridging gpu_lidar data #368

Open
roni-kreinin opened this issue Mar 7, 2023 · 9 comments
Open

Performance issues with bridging gpu_lidar data #368

roni-kreinin opened this issue Mar 7, 2023 · 9 comments
Labels
bug Something isn't working

Comments

@roni-kreinin
Copy link

Environment

  • OS Version: Ubuntu 22.04
  • ROS 2 Humble
  • Ignition Fortress
  • Source or binary build?
    Binary: 0.244.9

Description

The Create 3 sim uses a number of gpu_lidar sensors to simulate the IR intensity sensors as well as cliff detection sensors. The sensor data is bridged to ROS 2 with ros_gz_bridge and used by nodes. Performance of the simulation is reduced significantly as soon as the bridges for these sensors are added, and the topic frequency in ros2 is well below the desired update_rate specified in the urdf.

  • Expected behavior: LaserScan messages should be published at the set update_rate of the sensor.
  • Actual behavior: ros2 topic hz reports that topics are published at around 60% of the update rate. Additionally, the RTF in Gazebo drops significantly when the parameter_bridge nodes for the lidars are running.

Steps to reproduce

  1. Build create3_sim from source.
  2. ros2 launch irobot_create_ignition_bringup create_ignition.launch.py
  3. Check scan topic frequencies:
    ros2 topic hz /_internal/cliff_front_left/scan
    ros2 topic hz /_internal/ir_intensity_front_center_left/scan

For me the cliff sensors publish at around 47hz and the ir sensors at around 35hz. They both have update rates set to 62hz.
RTF also jumps between 40-60%.

  1. Disable the ir and cliff sensor bridges by commenting out lines 196 and 197 in create3_ros_ignition_bridge.launch.py. Launch the sim again.

With the bridges disabled I now have a steady RTF of around 90%.

  1. Re-enable the sensor bridges and uncap update_rate by commenting out line 58 in common_properties.urdf.xacro. Launch the sim again.

With this configuration, my RTF sits at a very consistent 31-33% without much fluctuation. Additionally, both cliff and IR sensors report around 160hz on their respective ros2 topics.

To achieve the desired 62hz, I have to set the update rate of the sensors to around 100hz. Clearly my machine is capable of publishing 160hz, so I am not sure what is causing this loss of ~1/3 the desired frequency. Additionally, why does the ros_gz_bridge cause such significantly reduced Gazebo RTF performance?

@roni-kreinin roni-kreinin added the bug Something isn't working label Mar 7, 2023
@roni-kreinin
Copy link
Author

@azeey Do you have any insight into this issue?

@azeey
Copy link
Contributor

azeey commented Mar 9, 2023

Without delving too deeply, I noticed that the launch file is creating one bridge node for all cliff sensors and one node for ir sensors. To improve performance, I recommend creating a node for each topic/sensor.

@roni-kreinin
Copy link
Author

@azeey I created separate nodes for each topic and sensor like this:

ir_bridges = GroupAction([
        Node(package='ros_gz_bridge', executable='parameter_bridge',
            name=ir + '_bridge',
            output='screen',
            parameters=[{
                'use_sim_time': use_sim_time
            }],
            arguments=[
                ['/world/', LaunchConfiguration('world'),
                '/model/', LaunchConfiguration('robot_name'),
                '/link/' + ir + '/sensor/' + ir + '/scan' +
                '@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan']
            ],
            remappings=[
                (['/world/', LaunchConfiguration('world'),
                    '/model/', LaunchConfiguration('robot_name'),
                    '/link/' + ir + '/sensor/' + ir + '/scan'],
                '_internal/' + ir + '/scan')
            ]) for ir in ir_intensity_sensors
    ])

Still seeing the same performance though. I also tested using the point cloud data instead of laserscans but it performed the same.

@roni-kreinin
Copy link
Author

From further investigation it seems that anything that subscribes to the /scan topics in ignition will cause a significant drop in performance. Do the sensors only publish topics when there is a subscriber?

@azeey
Copy link
Contributor

azeey commented Mar 9, 2023

Do the sensors only publish topics when there is a subscriber?

Yes, I believe so. So you might just be running into a compute limitation with your system. Are you using an NVIDIA GPU and is it configured properly?

@roni-kreinin
Copy link
Author

I am using a GTX 1650 and it is barely reaching 30% usage. My CPU is also only reaching around 40% utilisation.
Are there configurations I need to make specifically for gazebo?

Also as a separate question: is there a reason why ogre2 performs much worse than ogre as the render engine for sensors?

@roni-kreinin
Copy link
Author

There seems to be some sort of overhead in the gz-transport subscriber that prevents it from achieving the full update rate that is requested.

For example, if I replace the Subscribe line here with:

ignition::transport::SubscribeOptions opts;
opts.SetMsgsPerSec(30u);
node->Subscribe(topic_name, subCb, opts);

I would expect it to cap at 30 hz, since it was publishing at over 30hz uncapped before. But instead, I am seeing closer to 20 hz on the ros topic. The update rate on the sensor hasn't actually changed from 62hz.

@zp-yang
Copy link

zp-yang commented Mar 20, 2023

I think we are having the same problem see gz-sensors #332. I believe gpulidar, ir, and camera are all rendering sensors.

@ntfshard
Copy link

ntfshard commented Dec 25, 2024

Found interesting thing in https://github.com/gazebosim/gz-sensors/blob/gz-sensors9/src/GpuLidarSensor.cc#L132
(same expression in other sensors also presents)

Due to _memoryAligned is true, each point took 32 bytes; if change it to false, it will be 18 bytes AFAIS in PointCloudPacked.point_step msg field.
In other words, we are seems wasting around 40% of memory throughput here. I ran unit tests with this change and tests are passed. Tried to figure out what's happening in ros_gz but code is quite mysterious there.

I can make a PR with changing this in different sensors, if it's allowed change; just need a clarification/approve from codeowners
(I have not latest branch, so technically I can be wrong, but seems this code didn't changed a lot)

UPD: in rviz I able to see a pointcloud with this change (it includes ros_gz to convert gz->ros2 communication)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
Status: In progress
Development

No branches or pull requests

4 participants