-
Notifications
You must be signed in to change notification settings - Fork 342
Description
Hi Gazebo Dev Team,
First of all, thank you for the great software project. I've been using Gazebo Classic for a long time and it helped me a lot. In Gazebo Classic, switching from the CPU ray plugin to the GPU ray plugin resulted in a slight decrease in lidar accuracy. This was particularly noticeable when the lidar hit surfaces at shallow angles, though in most cases, the accuracy remained sufficient for our needs. However, after migrating from Gazebo Classic, the new "gpu_lidar" plugin appeared to be even more approximate than before. In my use cases, where scans are expected to come from spinning devices, this level of inaccuracy became problematic.
Below is a detailed problem description with accompanying images:
Test 1: Gazebo Classic
Setup:
- Ubuntu 22
- ROS 2 humble
- Gazebo Classic Version: 11.10.2 (installed from official APT repositories)
- Tested code is here: https://github.com/amock/rmcl_examples . However, I changed the field of view, number of samples, and resolution to make it equal to test 2 & 3.
CPU Ray Plugin
XML:
<gazebo reference="velodyne">
<sensor type="ray" name="velodyne-vlp16">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>128</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<resolution>1</resolution>
<min_angle>${-M_PI / 16.0}</min_angle>
<max_angle>${M_PI / 4.0}</max_angle>
</vertical>
</scan>
<range>
<min>0.3</min>
<max>130.0</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<ros>
<namespace>/velodyne</namespace>
<remapping>~/out:=points</remapping>
</ros>
<frame_name>velodyne</frame_name>
<organize_cloud>true</organize_cloud>
<min_range>0.9</min_range>
<max_range>130.0</max_range>
<gaussian_noise>0.008</gaussian_noise>
</plugin>
</sensor>
</gazebo>
Results (left Rviz, right Gazebo):
GPU Ray
XML:
<gazebo reference="velodyne">
<sensor type="gpu_ray" name="velodyne-vlp16">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>20</update_rate>
<ray>
<scan>
<horizontal>
<samples>128</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<resolution>1</resolution>
<min_angle>${-M_PI / 16.0}</min_angle>
<max_angle>${M_PI / 4.0}</max_angle>
</vertical>
</scan>
<range>
<min>0.3</min>
<max>130.0</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<ros>
<namespace>/velodyne</namespace>
<remapping>~/out:=points</remapping>
</ros>
<frame_name>velodyne</frame_name>
<organize_cloud>true</organize_cloud>
<min_range>0.9</min_range>
<max_range>130.0</max_range>
<gaussian_noise>0.008</gaussian_noise>
</plugin>
</sensor>
</gazebo>
Results (left Rviz, right Gazebo):
Note: Accuracy has slightly degraded compared to the CPU Ray. But it's still OK.
Test 2: Gazebo Fortress
Setup:
- Ubuntu 22
- ROS 2 humble
- Gazebo Fortress, from official APT repositories (Version see image)
- Code: https://github.com/naturerobots/mesh_navigation_tutorials/blob/main/mesh_navigation_tutorials_sim/urdf/ceres.urdf.xacro
GPU Raycaster:
<gazebo reference="laser3d">
<sensor name="laser3d" type="gpu_lidar">
<pose relative_to='laser3d'>0 0 0 0 0 0</pose>
<topic>/model/robot/cloud</topic>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>128</samples>
<resolution>1</resolution>
<min_angle>${-M_PI}</min_angle>
<max_angle>${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<resolution>1</resolution>
<min_angle>${-M_PI / 16.0}</min_angle>
<max_angle>${M_PI / 4.0}</max_angle>
</vertical>
</scan>
<range>
<min>0.2</min>
<max>100.0</max>
<resolution>0.001</resolution>
</range>
</ray>
<always_on>1</always_on>
<visualize>true</visualize>
<frame_id>laser3d</frame_id>
<gz_frame_id>laser3d</gz_frame_id>
<ign_frame_id>laser3d</ign_frame_id>
</sensor>
</gazebo>
Results (left RViz, right Gazebo):
Test 3: Gazebo Harmonic
- Ubuntu 24
- ROS 2 jazzy
- Gazebo Harmonic, from official APT repositories (Version see image)
- Code: Same as test 2
Same effects than in Gazebo Fortress:
Additional Tests
- Same effects for
ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.py
- Briefly tested under ROS 2 rolling. Problems remain.
Questions
- Did I do something wrong while parameterizing the new "gpu_lidar" plugin?
- Is this problem known?
- What causes the GPU LiDAR to have lower accuracy compared to the Gazebo Classic version?
- Unrelated to this issue: For Gazebo Harmonic, changing "gpu_lidar" to "lidar" was not working at all. Are the XML interfaces for "lidar" different then from a "gpu_lidar"?
Thanks for the help in advance
Alex
Metadata
Metadata
Assignees
Labels
Type
Projects
Status