forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathCMakeLists.txt
227 lines (188 loc) · 7.5 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
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
cmake_minimum_required(VERSION 3.14)
project(pointcloud_preprocessor)
find_package(autoware_cmake REQUIRED)
autoware_package()
# Suppress CGAL warning
set(CGAL_DATA_DIR ".")
find_package(OpenCV REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(Boost REQUIRED)
find_package(PCL REQUIRED)
find_package(CGAL REQUIRED COMPONENTS Core)
include_directories(
include
SYSTEM
${Boost_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
add_library(pointcloud_preprocessor_filter_base SHARED
src/filter.cpp
)
target_include_directories(pointcloud_preprocessor_filter_base PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
ament_target_dependencies(pointcloud_preprocessor_filter_base
message_filters
pcl_conversions
rclcpp
sensor_msgs
tf2_ros
tier4_autoware_utils
pcl_ros
)
add_library(faster_voxel_grid_downsample_filter SHARED
src/downsample_filter/faster_voxel_grid_downsample_filter.cpp
)
target_include_directories(faster_voxel_grid_downsample_filter PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)
ament_target_dependencies(faster_voxel_grid_downsample_filter
pcl_conversions
rclcpp
sensor_msgs
)
ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/utility/utilities.cpp
src/concatenate_data/concatenate_and_time_sync_nodelet.cpp
src/concatenate_data/concatenate_pointclouds.cpp
src/time_synchronizer/time_synchronizer_nodelet.cpp
src/crop_box_filter/crop_box_filter_nodelet.cpp
src/downsample_filter/voxel_grid_downsample_filter_nodelet.cpp
src/downsample_filter/random_downsample_filter_nodelet.cpp
src/downsample_filter/approximate_downsample_filter_nodelet.cpp
src/outlier_filter/ring_outlier_filter_nodelet.cpp
src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp
src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
src/passthrough_filter/passthrough_uint16.cpp
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
src/vector_map_filter/lanelet2_map_filter_nodelet.cpp
src/distortion_corrector/distortion_corrector.cpp
src/blockage_diag/blockage_diag_nodelet.cpp
src/polygon_remover/polygon_remover.cpp
src/vector_map_filter/vector_map_inside_area_filter.cpp
)
target_link_libraries(pointcloud_preprocessor_filter
pointcloud_preprocessor_filter_base
faster_voxel_grid_downsample_filter
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_LIBRARIES}
)
# ========== Time synchronizer ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PointCloudDataSynchronizerComponent"
EXECUTABLE time_synchronizer_node)
# ========== Concatenate data ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PointCloudConcatenationComponent"
EXECUTABLE concatenate_pointclouds_node)
# ========== Concatenate and Sync data ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent"
EXECUTABLE concatenate_data_node)
# ========== CropBox ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::CropBoxFilterComponent"
EXECUTABLE crop_box_filter_node)
# ========== Down Sampler Filter ==========
# -- Voxel Grid Downsample Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::VoxelGridDownsampleFilterComponent"
EXECUTABLE voxel_grid_downsample_filter_node)
# -- Random Downsample Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::RandomDownsampleFilterComponent"
EXECUTABLE random_downsample_filter_node)
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::ApproximateDownsampleFilterComponent"
EXECUTABLE approximate_downsample_filter_node)
# ========== Outlier Filter ==========
# -- Ring Outlier Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::RingOutlierFilterComponent"
EXECUTABLE ring_outlier_filter_node)
# -- Voxel Grid Outlier Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::VoxelGridOutlierFilterComponent"
EXECUTABLE voxel_grid_outlier_filter_node)
# -- Radius Search 2D Outlier Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::RadiusSearch2DOutlierFilterComponent"
EXECUTABLE radius_search_2d_outlier_filter_node)
# -- DualReturn Outlier Filter--
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::DualReturnOutlierFilterComponent"
EXECUTABLE dual_return_outlier_filter_node)
# ========== Passthrough Filter ==========
# -- Passthrough Filter --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PassThroughFilterComponent"
EXECUTABLE passthrough_filter_node)
# -- Passthrough Filter Uint16 --
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PassThroughFilterUInt16Component"
EXECUTABLE passthrough_filter_uint16_node)
# ========== Pointcloud Accumulator Filter ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PointcloudAccumulatorComponent"
EXECUTABLE pointcloud_accumulator_node)
# ========== Vector Map Filter ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::Lanelet2MapFilterComponent"
EXECUTABLE vector_map_filter_node)
# ========== Distortion Corrector ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::DistortionCorrectorComponent"
EXECUTABLE distortion_corrector_node)
# ========== Blockage Diagnostics ===========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::BlockageDiagComponent"
EXECUTABLE blockage_diag_node)
# ========== PolygonRemover ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PolygonRemoverComponent"
EXECUTABLE polygon_remover_node)
set(CGAL_DO_NOT_WARN_ABOUT_CMAKE_BUILD_TYPE TRUE)
target_link_libraries(polygon_remover_node gmp CGAL CGAL::CGAL CGAL::CGAL_Core)
# ========== Vector Map Inside Area Filter ===========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::VectorMapInsideAreaFilterComponent"
EXECUTABLE vector_map_inside_area_filter_node)
install(
TARGETS pointcloud_preprocessor_filter_base EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
install(
TARGETS faster_voxel_grid_downsample_filter EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)
install(
DIRECTORY include/
DESTINATION include/${PROJECT_NAME}
)
ament_export_targets(export_${PROJECT_NAME})
ament_auto_package(INSTALL_TO_SHARE
launch
config
)
if(BUILD_TESTING)
add_ros_test(
test/test_distortion_corrector.py
TIMEOUT "30"
)
add_ros_test(
test/test_distortion_corrector_use_imu_false.py
TIMEOUT "30"
)
endif()