Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

WIP: Make this a CMake-Package #53

Draft
wants to merge 9 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
build/

140 changes: 43 additions & 97 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,117 +1,63 @@
cmake_minimum_required(VERSION 3.10)
project(ndt_omp)
project(PCLOMP VERSION "1.0.0")

add_definitions(-std=c++14)
set(CMAKE_CXX_FLAGS "-std=c++14")
include(GNUInstallDirs)

if (BUILD_WITH_MARCH_NATIVE)
add_compile_options(-march=native)
else()
add_definitions(-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2)
set(CMAKE_CXX_FLAGS "-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2")
endif()
find_package(PCL 1.7 REQUIRED COMPONENTS registration)
find_package(OpenMP REQUIRED)

# pcl 1.7 causes a segfault when it is built with debug mode
set(CMAKE_BUILD_TYPE "RELEASE")

find_package(PCL 1.7 REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

message(STATUS "PCL_INCLUDE_DIRS:" ${PCL_INCLUDE_DIRS})
message(STATUS "PCL_LIBRARY_DIRS:" ${PCL_LIBRARY_DIRS})
message(STATUS "PCL_DEFINITIONS:" ${PCL_DEFINITIONS})

find_package(OpenMP)
if (OPENMP_FOUND)
set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
endif()

if($ENV{ROS_VERSION} EQUAL 1)
# ROS1
find_package(catkin REQUIRED COMPONENTS
roscpp
pcl_ros
set(HEADERS
src/pclomp/gicp_omp.h
src/pclomp/ndt_omp.h
src/pclomp/voxel_grid_covariance_omp.h
)

###################################
## catkin specific configuration ##
###################################
catkin_package(
INCLUDE_DIRS include
LIBRARIES ndt_omp
add_library(registration SHARED
src/voxel_grid_covariance_omp.cpp
src/ndt_omp.cpp
src/gicp_omp.cpp
)

###########
## Build ##
###########
include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
set_target_properties(registration PROPERTIES
PUBLIC_HEADER "${HEADERS}"
)

add_library(ndt_omp
src/pclomp/voxel_grid_covariance_omp.cpp
src/pclomp/ndt_omp.cpp
src/pclomp/gicp_omp.cpp
target_link_libraries(registration
PUBLIC ${PCL_REGISTRATION_LIBRARIES}
PRIVATE OpenMP::OpenMP_CXX
)

add_executable(align
apps/align.cpp
target_include_directories(registration PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/src>
$<INSTALL_INTERFACE:${CMAKE_INSTALL_INCLUDEDIR}>
${PCL_INCLUDE_DIRS}
)
add_dependencies(align
ndt_omp
)
target_link_libraries(align
${catkin_LIBRARIES}
${PCL_LIBRARIES}
ndt_omp
)

#############
## INSTALL ##
#############

install(
TARGETS
ndt_omp
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# Install binaries
install(TARGETS registration EXPORT pclomp-targets
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
PUBLIC_HEADER DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/pclomp
)

# install headers
install(DIRECTORY include/pclomp
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION})
else()

# ROS2
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

###########
## Build ##
###########
include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
# Export the library interface
install(EXPORT pclomp-targets
NAMESPACE pclomp::
DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/pclomp
)

add_library(ndt_omp
src/pclomp/voxel_grid_covariance_omp.cpp
src/pclomp/ndt_omp.cpp
src/pclomp/gicp_omp.cpp
# Create and install the version file
include(CMakePackageConfigHelpers)
write_basic_package_version_file("pclomp-config-version.cmake"
VERSION ${PCLOMP_VERSION}
COMPATIBILITY SameMajorVersion
)

target_link_libraries(ndt_omp ${PCL_LIBRARIES})

if(OpenMP_CXX_FOUND)
target_link_libraries(ndt_omp OpenMP::OpenMP_CXX)
else()
message(WARNING "OpenMP not found")
endif()

ament_auto_package()
endif()
install(
FILES
pclomp-config.cmake
${PROJECT_BINARY_DIR}/pclomp-config-version.cmake
DESTINATION
${CMAKE_INSTALL_LIBDIR}/cmake/pclomp
)
15 changes: 4 additions & 11 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,24 +1,17 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ndt_omp</name>
<version>0.0.0</version>
<name>pclomp</name>
<version>1.0.0</version>
<description>OpenMP boosted NDT and GICP algorithms</description>

<maintainer email="koide@aisl.cs.tut.ac.jp">koide</maintainer>

<license>BSD</license>

<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake_auto</buildtool_depend>

<depend condition="$ROS_VERSION == 1">pcl_ros</depend>
<depend condition="$ROS_VERSION == 1">roscpp</depend>

<depend condition="$ROS_VERSION == 2">libpcl-all-dev</depend>
<buildtool_depend>cmake</buildtool_depend>

<export>
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
<build_type>cmake</build_type>
</export>
</package>
2 changes: 2 additions & 0 deletions pclomp-config.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
find_package(PCL 1.7 REQUIRED COMPONENTS registration)
include("${CMAKE_CURRENT_LIST_DIR}/pclomp-targets.cmake")
2 changes: 1 addition & 1 deletion src/pclomp/gicp_omp.cpp → src/gicp_omp.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <pclomp/gicp_omp.h>
#include <pclomp/gicp_omp_impl.hpp>
#include <gicp_omp_impl.hpp>

template class pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>;
template class pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>;
Expand Down
File renamed without changes.
2 changes: 1 addition & 1 deletion src/pclomp/ndt_omp.cpp → src/ndt_omp.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <pclomp/ndt_omp.h>
#include <pclomp/ndt_omp_impl.hpp>
#include <ndt_omp_impl.hpp>

template class pclomp::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ>;
template class pclomp::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>;
2 changes: 1 addition & 1 deletion include/pclomp/ndt_omp_impl.hpp → src/ndt_omp_impl.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "ndt_omp.h"
#include <pclomp/ndt_omp.h>
/*
* Software License Agreement (BSD License)
*
Expand Down
File renamed without changes.
4 changes: 2 additions & 2 deletions include/pclomp/ndt_omp.h → src/pclomp/ndt_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

#include <pcl/registration/registration.h>
#include <pcl/search/impl/search.hpp>
#include "voxel_grid_covariance_omp.h"
#include <pclomp/voxel_grid_covariance_omp.h>

#include <unsupported/Eigen/NonLinearOptimization>

Expand Down Expand Up @@ -181,7 +181,7 @@ namespace pclomp
* \param[in] outlier_ratio outlier ratio
*/
inline void
setOutlierRatio(double outlier_ratio)
setOulierRatio(double outlier_ratio)
{
outlier_ratio_ = outlier_ratio;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <pclomp/voxel_grid_covariance_omp.h>
#include <pclomp/voxel_grid_covariance_omp_impl.hpp>
#include <voxel_grid_covariance_omp_impl.hpp>

template class pclomp::VoxelGridCovariance<pcl::PointXYZ>;
template class pclomp::VoxelGridCovariance<pcl::PointXYZI>;
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

#include <pcl/common/common.h>
#include <pcl/filters/boost.h>
#include "voxel_grid_covariance_omp.h"
#include <pclomp/voxel_grid_covariance_omp.h>
#include <Eigen/Dense>
#include <Eigen/Cholesky>

Expand Down