Skip to content

Commit

Permalink
Updated Velodyne Plugins, for Mint 19 support
Browse files Browse the repository at this point in the history
  • Loading branch information
Jeffrey committed Oct 13, 2019
1 parent 117a179 commit a8d4a21
Show file tree
Hide file tree
Showing 20 changed files with 381 additions and 137 deletions.
Empty file removed velodyne_lidar/.Rhistory
Empty file.
2 changes: 1 addition & 1 deletion velodyne_lidar/LICENSE
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
Software License Agreement (BSD License)

Copyright (c) 2015-2017, Dataspeed Inc.
Copyright (c) 2015-2018, Dataspeed Inc.
All rights reserved.

Redistribution and use in source and binary forms, with or without modification,
Expand Down
15 changes: 13 additions & 2 deletions velodyne_lidar/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,29 +5,36 @@ URDF description and Gazebo plugins to simulate Velodyne laser scanners

# Features
* URDF with colored meshes
* Gazebo plugin based on [gazeboo_plugins/gazebo_ros_block_laser](https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_block_laser.cpp)
* Gazebo plugin based on [gazebo_plugins/gazebo_ros_block_laser](https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_block_laser.cpp)
* Publishes PointCloud2 with same structure (x, y, z, intensity, ring)
* Simulated Gaussian noise
* GPU acceleration ([with a modern Gazebo build](gazebo_upgrade.md))
* Supported models:
* [VLP-16](velodyne_description/urdf/VLP-16.urdf.xacro)
* [HDL-32E](velodyne_description/urdf/HDL-32E.urdf.xacro)
* Pull requests for other models are welcome
* Experimental support for clipping low-intensity returns

# Parameters
* ```*origin``` URDF transform from parent link.
* ```parent``` URDF parent link name. Default ```base_link```
* ```name``` URDF model name. Also used as tf frame_id for PointCloud2 output. Default ```velodyne```
* ```topic``` PointCloud2 output topic name. Default ```/velodyne_points```
* ```hz``` Update rate in hz. Default ```10```
* ```lasers``` Number of vertical spinning lasers. Default ```VLP-16: 16, HDL-32E: 33```
* ```lasers``` Number of vertical spinning lasers. Default ```VLP-16: 16, HDL-32E: 32```
* ```samples``` Nuber of horizontal rotating samples. Default ```VLP-16: 1875, HDL-32E: 2187```
* ```min_range``` Minimum range value in meters. Default ```0.9```
* ```max_range``` Maximum range value in meters. Default ```130.0```
* ```noise``` Gausian noise value in meters. Default ```0.008```
* ```min_angle``` Minimum horizontal angle in radians. Default ```-3.14```
* ```max_angle``` Maximum horizontal angle in radians. Default ```3.14```
* ```gpu``` Use gpu_ray sensor instead of the standard ray sensor. Default ```false```
* ```min_intensity``` The minimum intensity beneath which returns will be clipped. Can be used to remove low-intensity objects.

# Known Issues
* 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](https://bitbucket.org/osrf/gazebo/issues/946/),[image](img/gpu.png))
* Solution: Upgrade to a [modern Gazebo version](gazebo_upgrade.md)
* 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](velodyne_description/urdf/example.urdf.xacro)
* Gazebo crashes when updating HDL-32E sensors with default number of points. "Took over 1.0 seconds to update a sensor."
Expand All @@ -37,3 +44,7 @@ URDF description and Gazebo plugins to simulate Velodyne laser scanners

# Example Gazebo Robot
```roslaunch velodyne_description example.launch```

# Example Gazebo Robot (with GPU)
```roslaunch velodyne_description example.launch gpu:=true```

56 changes: 47 additions & 9 deletions velodyne_lidar/bitbucket-pipelines.yml
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,50 @@ image: osrf/ros:kinetic-desktop-full

pipelines:
default:
- step:
script:
- mkdir -p /tmp/src/repo && mv `pwd`/* /tmp/src/repo && mv /tmp/src `pwd` # Move everything into the src directory
- source `find /opt/ros -name setup.bash | sort | head -1` && echo $ROS_DISTRO # Source ROS environment
- apt update && rosdep install --from-paths src --ignore-src -y # Install dependencies missing from the docker image
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args tests
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args run_tests
- catkin_test_results build_isolated
- parallel:
- step:
name: kinetic
image: osrf/ros:kinetic-desktop-full
script:
- mkdir -p /tmp/src/repo && mv `pwd`/* /tmp/src/repo && mv /tmp/src `pwd` # Move everything into the src directory
- source `find /opt/ros -name setup.bash | sort | head -1` && echo $ROS_DISTRO # Source ROS environment
- apt update && rosdep install --from-paths src --ignore-src -y # Install dependencies missing from the docker image
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args tests
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args run_tests -j1
- catkin_test_results build_isolated
- step:
name: lunar
image: osrf/ros:lunar-desktop-full
script:
- mkdir -p /tmp/src/repo && mv `pwd`/* /tmp/src/repo && mv /tmp/src `pwd` # Move everything into the src directory
- source `find /opt/ros -name setup.bash | sort | head -1` && echo $ROS_DISTRO # Source ROS environment
- apt update && rosdep install --from-paths src --ignore-src -y # Install dependencies missing from the docker image
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args tests
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args run_tests -j1
- catkin_test_results build_isolated
- step:
name: melodic
image: osrf/ros:melodic-desktop-full
script:
- mkdir -p /tmp/src/repo && mv `pwd`/* /tmp/src/repo && mv /tmp/src `pwd` # Move everything into the src directory
- source `find /opt/ros -name setup.bash | sort | head -1` && echo $ROS_DISTRO # Source ROS environment
- apt update && rosdep install --from-paths src --ignore-src -y # Install dependencies missing from the docker image
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args tests
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args run_tests -j1
- catkin_test_results build_isolated
branches:
gazebo2:
- step:
name: indigo
image: osrf/ros:indigo-desktop-full
script:
- mkdir -p /tmp/src/repo && mv `pwd`/* /tmp/src/repo && mv /tmp/src `pwd` # Move everything into the src directory
- source `find /opt/ros -name setup.bash | sort | head -1` && echo $ROS_DISTRO # Source ROS environment
- apt update && rosdep install --from-paths src --ignore-src -y # Install dependencies missing from the docker image
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args tests
- catkin_make_isolated --install -DCMAKE_BUILD_TYPE=Release --make-args run_tests -j1
- catkin_test_results build_isolated
14 changes: 14 additions & 0 deletions velodyne_lidar/gazebo_upgrade.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# GPU issues
The GPU problems reported in this [issue](https://bitbucket.org/osrf/gazebo/issues/946/) have been solved with this [pull request](https://bitbucket.org/osrf/gazebo/pull-requests/2955/) for the ```gazebo7``` branch. The Gazebo versions from the ROS apt repository (7.0.0 for Kinetic, 9.0.0 for Melodic) do not have this fix. One solution is to pull up-to-date packages from the OSRF Gazebo apt repository. Another solution is to compile from source: http://gazebosim.org/tutorials?tut=install_from_source

* The GPU fix was added to ```gazebo7``` in version 7.14.0
* The GPU fix was added to ```gazebo9``` in version 9.4.0

# Use up-to-date packages from the OSRF Gazebo apt repository
```
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/gazebo-stable.list'
sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys D2486D2DD83DB69272AFE98867170598AF249743
sudo apt update
sudo apt upgrade
```

Binary file added velodyne_lidar/img/gpu.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
13 changes: 13 additions & 0 deletions velodyne_lidar/velodyne_description/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,19 @@
Changelog for package velodyne_description
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.0.9 (2019-03-08)
------------------

1.0.8 (2018-09-08)
------------------

1.0.7 (2018-07-03)
------------------
* Added GPU support
* Updated inertia tensors for VLP-16 and HDL-32E to realistic values
* Removed unnecessary file extraction code in cmake
* Contributors: Kevin Hallenbeck, Max Schwarz

1.0.6 (2017-10-17)
------------------
* Use robotNamespace as prefix for PointCloud2 topic frame_id by default
Expand Down
10 changes: 0 additions & 10 deletions velodyne_lidar/velodyne_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,6 @@ find_package(catkin REQUIRED)

catkin_package()

# Extract *.tar.gz files in the mesh folder
FILE(GLOB files RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}/meshes" "${CMAKE_CURRENT_SOURCE_DIR}/meshes/*.tar.gz")
FOREACH(filename ${files})
MESSAGE(STATUS "Extracting file: ${filename}")
execute_process(
COMMAND ${CMAKE_COMMAND} -E tar xzf ${filename}
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/meshes
)
ENDFOREACH(filename)

install(DIRECTORY launch meshes rviz urdf world
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
3 changes: 2 additions & 1 deletion velodyne_lidar/velodyne_description/launch/example.launch
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@
</include>

<!-- Spawn the example robot -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find velodyne_description)/urdf/example.urdf.xacro'" />
<arg name="gpu" default="false"/>
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find velodyne_description)/urdf/example.urdf.xacro' gpu:=$(arg gpu)" />
<node pkg="gazebo_ros" type="spawn_model" name="spawn_model" args="-urdf -param /robot_description -model example"/>
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="30.0" />
Expand Down
2 changes: 1 addition & 1 deletion velodyne_lidar/velodyne_description/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>velodyne_description</name>
<version>1.0.6</version>
<version>1.0.9</version>
<description>
URDF and meshes describing Velodyne laser scanners.
</description>
Expand Down
120 changes: 81 additions & 39 deletions velodyne_lidar/velodyne_description/urdf/HDL-32E.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="HDL-32E">
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:macro name="HDL-32E" params="*origin parent:=base_link name:=velodyne topic:=/velodyne_points hz:=10 lasers:=32 samples:=2187 collision_range:=0.3 min_range:=0.9 max_range:=130.0 noise:=0.008 min_angle:=-${M_PI} max_angle:=${M_PI}">
<xacro:macro name="HDL-32E" params="*origin parent:=base_link name:=velodyne topic:=/velodyne_points hz:=10 lasers:=32 samples:=2187 collision_range:=0.3 min_range:=0.9 max_range:=130.0 noise:=0.008 min_angle:=-${M_PI} max_angle:=${M_PI} gpu:=false">

<joint name="${name}_base_mount_joint" type="fixed">
<xacro:insert_block name="origin" />
Expand Down Expand Up @@ -52,44 +52,86 @@

<!-- Gazebo requires the velodyne_gazebo_plugins package -->
<gazebo reference="${name}">
<sensor type="ray" name="${name}-HDL32E">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${hz}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${min_angle}</min_angle>
<max_angle>${max_angle}</max_angle>
</horizontal>
<vertical>
<samples>${lasers}</samples>
<resolution>1</resolution>
<min_angle>-${30.67*M_PI/180.0}</min_angle>
<max_angle> ${10.67*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${collision_range}</min>
<max>${max_range+1}</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">
<topicName>${topic}</topicName>
<frameName>${name}</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>${noise}</gaussianNoise>
</plugin>
</sensor>
<xacro:if value="${gpu}">
<sensor type="gpu_ray" name="${name}-HDL32E">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${hz}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${min_angle}</min_angle>
<max_angle>${max_angle}</max_angle>
</horizontal>
<vertical>
<samples>${lasers}</samples>
<resolution>1</resolution>
<min_angle>-${30.67*M_PI/180.0}</min_angle>
<max_angle> ${10.67*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${collision_range}</min>
<max>${max_range+1}</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_gpu_laser.so">
<topicName>${topic}</topicName>
<frameName>${name}</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>${noise}</gaussianNoise>
</plugin>
</sensor>
</xacro:if>
<xacro:unless value="${gpu}">
<sensor type="ray" name="${name}-HDL32E">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${hz}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${min_angle}</min_angle>
<max_angle>${max_angle}</max_angle>
</horizontal>
<vertical>
<samples>${lasers}</samples>
<resolution>1</resolution>
<min_angle>-${30.67*M_PI/180.0}</min_angle>
<max_angle> ${10.67*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${collision_range}</min>
<max>${max_range+1}</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">
<topicName>${topic}</topicName>
<frameName>${name}</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>${noise}</gaussianNoise>
</plugin>
</sensor>
</xacro:unless>
</gazebo>

</xacro:macro>
Expand Down
Loading

0 comments on commit a8d4a21

Please sign in to comment.