URDF description and Gazebo plugins to simulate Velodyne laser scanners
- URDF with colored meshes
- Gazebo plugin based on gazebo_plugins/gazebo_ros_block_laser
- Publishes PointCloud2 with same structure (x, y, z, intensity, ring, time)
- Simulated Gaussian noise
- GPU acceleration (with a modern Gazebo build)
- Supported models:
- Experimental support for clipping low-intensity returns
*origin
URDF transform from parent link.parent
URDF parent link name. Defaultbase_link
name
URDF model name. Also used as tf frame_id for PointCloud2 output. Defaultvelodyne
topic
PointCloud2 output topic name. Default/velodyne_points
hz
Update rate in hz. Default10
lasers
Number of vertical spinning lasers. DefaultVLP-16: 16, HDL-32E: 32
samples
Nuber of horizontal rotating samples. DefaultVLP-16: 1875, HDL-32E: 2187
organize_cloud
Organize PointCloud2 into 2D array with NaN placeholders, otherwise 1D array and leave out invlaid points. Defaultfalse
min_range
Minimum range value in meters. Default0.9
max_range
Maximum range value in meters. Default130.0
noise
Gausian noise value in meters. Default0.008
min_angle
Minimum horizontal angle in radians. Default-3.14
max_angle
Maximum horizontal angle in radians. Default3.14
gpu
Use gpu_ray sensor instead of the standard ray sensor. Defaultfalse
min_intensity
The minimum intensity beneath which returns will be clipped. Can be used to remove low-intensity objects.
- At full sample resolution, Gazebo can take up to 30 seconds to load the VLP-16 pluggin, 60 seconds for the HDL-32E
- With the default Gazebo version shipped with ROS, ranges are incorrect when accelerated with the GPU option (issue,image)
- Solution: Upgrade to a modern Gazebo version
- Gazebo cannot maintain 10Hz with large pointclouds
- Solution: User can reduce number of points (samples) or frequency (hz) in the urdf parameters, see example.urdf.xacro
- Gazebo crashes when updating HDL-32E sensors with default number of points. "Took over 1.0 seconds to update a sensor."
- Solution: User can reduce number of points in urdf (same as above)
roslaunch velodyne_description example.launch
roslaunch velodyne_description example.launch gpu:=true