-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathCMakeLists.txt
135 lines (108 loc) · 4.64 KB
/
CMakeLists.txt
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
cmake_minimum_required(VERSION 2.8.3)
project(alignment_checker)
set (CMAKE_CXX_STANDARD 14)
set(CMAKE_BUILD_TYPE release)
IF(CMAKE_SIZEOF_VOID_P EQUAL 4)
SET(LIB_SUFFIX "")
ELSE(CMAKE_SIZEOF_VOID_P EQUAL 4)
SET(LIB_SUFFIX 64)
ENDIF(CMAKE_SIZEOF_VOID_P EQUAL 4)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fvisibility=hidden")
set(PYBIND11_PYTHON_VERSION 3.8 CACHE STRING "")
find_package(pybind11 REQUIRED)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(PCL 1.7 REQUIRED)
find_package(OpenCV REQUIRED)
find_package(catkin REQUIRED
geometry_msgs
cmake_modules
eigen_conversions
pcl_ros
roscpp
rospy
sensor_msgs
std_msgs
tf_conversions
tf
genmsg
cv_bridge
tf_conversions
cfear_radarodometry
#ndt_map
#robust_mapping_custom_msgs
message_generation
)
add_service_files(
FILES
AlignmentData.srv
)
generate_messages(
DEPENDENCIES
)
find_package(OpenMP REQUIRED)
if(OPENMP_FOUND)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
endif()
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS geometry_msgs eigen_conversions pcl_ros roscpp rospy sensor_msgs std_msgs tf_conversions tf genmsg tf_conversions cfear_radarodometry message_generation #cmake_modules #ndt_map
)
INCLUDE_DIRECTORIES ( $ENV{EIGEN3_INCLUDE_DIR} ${OpenCV_INCLUDE_DIRS})
include_directories( include ${Boost_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} )
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
set (${PROJECT_NAME}_LIB_SRCS
src/alignment_checker/AlignmentQuality.cpp
src/alignment_checker/ScanEvaluator.cpp
src/alignment_checker/DataHandler.cpp
src/alignment_checker/Utils.cpp
src/alignment_checker/ScanType.cpp
src/alignment_checker/alignmentinterface.cpp
#src/alignment_checker/scan.cpp
#src/alignment_checker/scancomparsion.cpp
#src/alignment_checker/alignmenttester.cpp
#src/alignment_checker/viewer.cpp
#src/alignment_checker/ndtScanComparsion.cpp ##uncomment if ndt libraries are not being used, this is only used for evaluation
)
add_library(${PROJECT_NAME} ${${PROJECT_NAME}_LIB_SRCS})
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} pcl_common ${OpenCV_LIBS} pybind11::embed)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
# ${catkin_INCLUDE_DIRS}
)
#add_definitions(${PCL_DEFINITIONS})
#link_directories(${PCL_LIBRARY_DIRS})
add_executable(evaluate_scans src/evaluate_scans.cpp )
target_link_libraries(evaluate_scans ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
catkin_install_python(PROGRAMS python/alignment_service.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
catkin_add_gtest(${PROJECT_NAME}_python_classifier_test test/python_classifier_interface_tests.cpp)
catkin_add_gtest(${PROJECT_NAME}_scan_learning_test test/scan_learning_interface_tests.cpp)
#if(TARGET ${PROJECT_NAME}_python_classifier_test)
target_link_libraries(${PROJECT_NAME}_python_classifier_test ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#endif()
#if(TARGET ${PROJECT_NAME}_scan_learning_test)
target_link_libraries(${PROJECT_NAME}_scan_learning_test ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#endif()
#add_executable(test_align src/test_alignment.cpp )
#target_link_libraries(test_align ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#add_executable(score_viewer src/score_viewer.cpp )
#target_link_libraries(score_viewer ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#add_executable(function_surface src/function_surface.cpp )
#target_link_libraries(function_surface ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#add_executable(CorAlServer src/CorAlServer.cpp )
#target_link_libraries(CorAlServer ${catkin_LIBRARIES} ${Boost_LIBRARIES} $ENV{EIGEN3_INCLUDE_DIR} ${PROJECT_NAME} ${PCL_LIBRARIES})
#add_definitions(${PCL_DEFINITIONS})