Skip to content

Commit

Permalink
Velodyne pcl (ros-drivers#335)
Browse files Browse the repository at this point in the history
* fix time assignment in organized cloud container

* add velodyne_pcl package with point_types.h

* add README.md with infos for conversion

* rename containers to cover the added time property

* Adding roslint to velodyne_pcl. (#1)

* Update CMake version to 3.5

* Update package.xml to Format2 and package version to 1.5.2

* Update ros package format

Co-authored-by: Joshua Whitley <josh.whitley@autoware.org>
  • Loading branch information
2 people authored and wep21 committed Mar 3, 2022
1 parent faa0eb1 commit d49d4fd
Show file tree
Hide file tree
Showing 5 changed files with 198 additions and 0 deletions.
35 changes: 35 additions & 0 deletions velodyne_pcl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
cmake_minimum_required(VERSION 3.5)
project(velodyne_pcl)

### Compile options
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
endif()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

find_package(PCL REQUIRED COMPONENTS common)

ament_auto_add_library(${PROJECT_NAME} SHARED
src/velodyne_pcl.cpp
)

target_include_directories(${PROJECT_NAME}
PUBLIC ${PCL_COMMON_INCLUDE_DIRS}
)

target_link_libraries(${PROJECT_NAME}
${PCL_LIBRARIES}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package()

32 changes: 32 additions & 0 deletions velodyne_pcl/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
## PointCloud2 to PCL PointCloud Conversion

Convert `sensor_msgs::msg::PointCloud2` objects coming from the velodyne_pointcloud driver to `pcl::PointCloud<velodyne_pcl::PointXYZIRT>` objects.

The `sensor_msgs::msg::PointCloud2` ROS message is constructed by using the `PointcloudXYZIRT`, or the `OrganizedCloudXYZIRT` container.
Both define the following channels:

* x - The x coord in Cartesian coordinates
* y - The y coord in Cartesian coordinates
* z - The z coord in Cartesian coordinates
* intensity - The measured intensity at the point
* ring - The ring number of the laser
* time - The time stamp of the measured point

To convert a `sensor_msgs::msg::PointCloud2` published by the velodyne driver to PCL you could use the following code:

```
#include <pcl_conversions/pcl_conversions.h>
#include <velodyne_pcl/point_types.hpp>
#include <pcl/PCLPointCloud2.h>
#include <pcl/conversions.h>
void cloud_callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloud){
pcl::PCLPointCloud2 pcl_pointcloud2;
pcl_conversions::toPCL(*cloud, pcl_pointcloud2);
pcl::PointCloud<velodyne_pcl::PointXYZIRT>::Ptr pcl_cloud_ptr(new pcl::PointCloud<velodyne_pcl::PointXYZIRT>);
pcl::fromPCLPointCloud2(pcl_pointcloud2, *pcl_cloud_ptr);
// use pcl_cloud_ptr
}
```
71 changes: 71 additions & 0 deletions velodyne_pcl/include/velodyne_pcl/point_types.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// Copyright 2012 - 2020 Austin Robot Technology, Jesse Vera, Jack O'Quin, Piyush Khandelwal, Joshua Whitley, Sebastian Pütz // NOLINT
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of {copyright_holder} nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

/** \file
*
* Point Cloud Library point structures for Velodyne data.
*
* @author Jesse Vera
* @author Jack O'Quin
* @author Piyush Khandelwal
* @author Sebastian Pütz
*/

#ifndef VELODYNE_PCL__POINT_TYPES_HPP_
#define VELODYNE_PCL__POINT_TYPES_HPP_

#include <pcl/point_types.h>

namespace velodyne_pcl
{
struct PointXYZIRT
{
PCL_ADD_POINT4D; // quad-word XYZ
float intensity; ///< laser intensity reading
uint16_t ring; ///< laser ring number
float time; ///< laser time reading
EIGEN_MAKE_ALIGNED_OPERATOR_NEW // ensure proper alignment
}
EIGEN_ALIGN16;
} // namespace velodyne_pcl

// *INDENT-OFF*
POINT_CLOUD_REGISTER_POINT_STRUCT(velodyne_pcl::PointXYZIRT,
(float, x, x)
(float, y, y)
(float, z, z)
(float, intensity, intensity)
(uint16_t, ring, ring)
(float, time, time))
// *INDENT-ON*

#endif // VELODYNE_PCL__POINT_TYPES_HPP_
27 changes: 27 additions & 0 deletions velodyne_pcl/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>velodyne_pcl</name>
<version>1.5.2</version>
<description>The velodyne_pcl package</description>

<maintainer email="josh.whitley@autoware.org">Josh Whitley</maintainer>

<license>BSD</license>

<url type="website">http://wiki.ros.org/velodyne_pcl</url>
<url type="repository">https://github.com/ros-drivers/velodyne</url>
<url type="bugtracker">https://github.com/ros-drivers/velodyne/issues</url>

<author>Sebastian Pütz</author>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>libpcl-all-dev</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
33 changes: 33 additions & 0 deletions velodyne_pcl/src/velodyne_pcl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// Copyright 2012 - 2020 Austin Robot Technology, Jesse Vera, Jack O'Quin, Piyush Khandelwal, Joshua Whitley, Sebastian Pütz // NOLINT
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of {copyright_holder} nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#include "velodyne_pcl/point_types.hpp"

0 comments on commit d49d4fd

Please sign in to comment.