-
Notifications
You must be signed in to change notification settings - Fork 455
/
CMakeLists.txt
130 lines (118 loc) · 4.26 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
cmake_minimum_required(VERSION 2.8.3)
project(lvi_sam)
######################
### Cmake flags
######################
set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_CXX_FLAGS "-std=c++11")
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g -pthread")
######################
### Packages
######################
find_package(catkin REQUIRED COMPONENTS
tf
roscpp
rospy
roslib
# msg
std_msgs
sensor_msgs
geometry_msgs
nav_msgs
# cv
cv_bridge
# pcl
pcl_conversions
# msg generation
message_generation
)
find_package(OpenMP REQUIRED)
find_package(PCL REQUIRED)
find_package(OpenCV REQUIRED)
find_package(Ceres REQUIRED)
find_package(GTSAM REQUIRED QUIET)
find_package(Boost REQUIRED COMPONENTS filesystem program_options system timer)
######################
### Message generation
######################
add_message_files(
DIRECTORY msg
FILES
cloud_info.msg
)
generate_messages(
DEPENDENCIES
geometry_msgs
std_msgs
nav_msgs
sensor_msgs
)
######################
### Catkin
######################
catkin_package(
DEPENDS PCL GTSAM
)
include_directories(
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GTSAM_INCLUDE_DIR}
)
link_directories(
${PCL_LIBRARY_DIRS}
${OpenCV_LIBRARY_DIRS}
${GTSAM_LIBRARY_DIRS}
)
######################
### visual odometry
######################
file(GLOB visual_feature_files
"src/visual_odometry/visual_feature/*.cpp"
"src/visual_odometry/visual_feature/camera_models/*.cc"
)
file(GLOB visual_odometry_files
"src/visual_odometry/visual_estimator/*.cpp"
"src/visual_odometry/visual_estimator/factor/*.cpp"
"src/visual_odometry/visual_estimator/initial/*.cpp"
"src/visual_odometry/visual_estimator/utility/*.cpp"
)
file(GLOB visual_loop_files
"src/visual_odometry/visual_loop/*.cpp"
"src/visual_odometry/visual_loop/utility/*.cpp"
"src/visual_odometry/visual_loop/ThirdParty/*.cpp"
"src/visual_odometry/visual_loop/ThirdParty/DBoW/*.cpp"
"src/visual_odometry/visual_loop/ThirdParty/DUtils/*.cpp"
"src/visual_odometry/visual_loop/ThirdParty/DVision/*.cpp"
"src/visual_odometry/visual_feature/camera_models/*.cc"
)
# Visual Feature Tracker
add_executable(${PROJECT_NAME}_visual_feature ${visual_feature_files})
target_link_libraries(${PROJECT_NAME}_visual_feature ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES})
# Visual Odometry
add_executable(${PROJECT_NAME}_visual_odometry ${visual_odometry_files})
target_link_libraries(${PROJECT_NAME}_visual_odometry ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES})
# Visual Lopp
add_executable(${PROJECT_NAME}_visual_loop ${visual_loop_files})
target_link_libraries(${PROJECT_NAME}_visual_loop ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} ${CERES_LIBRARIES})
######################
### lidar odometry
######################
# IMU Preintegration
add_executable(${PROJECT_NAME}_imuPreintegration src/lidar_odometry/imuPreintegration.cpp)
target_link_libraries(${PROJECT_NAME}_imuPreintegration ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} gtsam Boost::timer)
# Range Image Projection
add_executable(${PROJECT_NAME}_imageProjection src/lidar_odometry/imageProjection.cpp)
add_dependencies(${PROJECT_NAME}_imageProjection ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(${PROJECT_NAME}_imageProjection ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})
# Feature Association
add_executable(${PROJECT_NAME}_featureExtraction src/lidar_odometry/featureExtraction.cpp)
add_dependencies(${PROJECT_NAME}_featureExtraction ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(${PROJECT_NAME}_featureExtraction ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})
# Mapping Optimization
add_executable(${PROJECT_NAME}_mapOptmization src/lidar_odometry/mapOptmization.cpp)
add_dependencies(${PROJECT_NAME}_mapOptmization ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)
target_compile_options(${PROJECT_NAME}_mapOptmization PRIVATE ${OpenMP_CXX_FLAGS})
target_link_libraries(${PROJECT_NAME}_mapOptmization PRIVATE ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} ${OpenMP_CXX_FLAGS} gtsam Boost::timer)