From 6c9d3376df72278e40448e5bdfc91e5cceb0ee1f Mon Sep 17 00:00:00 2001 From: matlabbe Date: Wed, 29 Aug 2018 15:02:16 -0400 Subject: [PATCH] Fixed some compilation errors and a linker error when including the library in another project. --- CMakeLists.txt | 5 +++-- include/loam_velodyne/BasicLaserMapping.h | 2 ++ include/loam_velodyne/MultiScanRegistration.h | 2 +- package.xml | 2 ++ 4 files changed, 8 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b2823d4..8297219 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,7 +8,8 @@ find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs - tf) + tf + pcl_conversions) find_package(Eigen3 REQUIRED) find_package(PCL REQUIRED) @@ -20,7 +21,7 @@ include_directories( ${PCL_INCLUDE_DIRS}) catkin_package( - CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs + CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs tf pcl_conversions DEPENDS EIGEN3 PCL INCLUDE_DIRS include LIBRARIES loam diff --git a/include/loam_velodyne/BasicLaserMapping.h b/include/loam_velodyne/BasicLaserMapping.h index fbdc3a6..cf55efe 100644 --- a/include/loam_velodyne/BasicLaserMapping.h +++ b/include/loam_velodyne/BasicLaserMapping.h @@ -96,6 +96,7 @@ class BasicLaserMapping auto& downSizeFilterCorner() { return _downSizeFilterCorner; } auto& downSizeFilterSurf() { return _downSizeFilterSurf; } + auto& downSizeFilterMap() { return _downSizeFilterMap; } auto frameCount() const { return _frameCount; } auto scanPeriod() const { return _scanPeriod; } @@ -177,6 +178,7 @@ class BasicLaserMapping pcl::VoxelGrid _downSizeFilterCorner; ///< voxel filter for down sizing corner clouds pcl::VoxelGrid _downSizeFilterSurf; ///< voxel filter for down sizing surface clouds + pcl::VoxelGrid _downSizeFilterMap; ///< voxel filter for down sizing accumulated map bool _downsizedMapCreated = false; }; diff --git a/include/loam_velodyne/MultiScanRegistration.h b/include/loam_velodyne/MultiScanRegistration.h index cb7d678..6d2a5d2 100644 --- a/include/loam_velodyne/MultiScanRegistration.h +++ b/include/loam_velodyne/MultiScanRegistration.h @@ -77,7 +77,7 @@ class MultiScanMapper { * @param angle the vertical point angle (in rad) * @return the ring ID */ - inline int getRingForAngle(const float& angle); + int getRingForAngle(const float& angle); /** Multi scan mapper for Velodyne VLP-16 according to data sheet. */ static inline MultiScanMapper Velodyne_VLP_16() { return MultiScanMapper(-15, 15, 16); }; diff --git a/package.xml b/package.xml index 9b1a98a..eba3e34 100644 --- a/package.xml +++ b/package.xml @@ -24,6 +24,7 @@ std_msgs sensor_msgs tf + pcl_conversions geometry_msgs nav_msgs @@ -32,6 +33,7 @@ rospy std_msgs tf + pcl_conversions rostest rosbag