-
Notifications
You must be signed in to change notification settings - Fork 19
/
Copy pathCMakeLists.txt
195 lines (170 loc) · 6.81 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
cmake_minimum_required(VERSION 3.18) # 3.18 To automatically detect CUDA_ARCHITECTURES
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CUDA_STANDARD 17)
# Build Release by default; CMAKE_BUILD_TYPE needs to be set before project(...)
if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE "Release" CACHE STRING
"Choose the type of build, options are: Debug Release RelWithDebInfo MinSizeRel" FORCE)
endif(NOT CMAKE_BUILD_TYPE)
project(RobotecGPULidar C CXX CUDA)
# Logging default settings (can be changed via API call)
set(RGL_LOG_STDOUT ON CACHE BOOL
"Enables logging to STDOUT")
set(RGL_LOG_LEVEL INFO CACHE STRING
"Specifies minimal severity of log message to be printed (TRACE, DEBUG, INFO, WARN, ERROR, CRITICAL, OFF)")
set(RGL_LOG_FILE "" CACHE STRING # STRING prevents from expanding relative paths
"Defines a file path to store RGL log")
set(RGL_AUTO_TAPE_PATH "" CACHE STRING # STRING prevents from expanding relative paths
"If non-empty, defines a path for the automatic tape (started on the first API call)")
# Test configuration
set(RGL_BUILD_TESTS ON CACHE BOOL
"Enables building test. GTest will be automatically downloaded")
# Tools configuration
set(RGL_BUILD_TOOLS ON CACHE BOOL "Enables building RGL executable tools")
# Extensions configuration
set(RGL_BUILD_PCL_EXTENSION OFF CACHE BOOL
"Enables building PCL extension.")
set(RGL_BUILD_ROS2_EXTENSION OFF CACHE BOOL
"Enables building ROS2 extension. It requires installed and sourced ROS2.")
set(RGL_BUILD_ROS2_EXTENSION_STANDALONE OFF CACHE BOOL
"Enables building ROS2 extension in standalone mode. It requires installed and sourced ROS2.")
if (RGL_BUILD_ROS2_EXTENSION_STANDALONE)
set(RGL_BUILD_ROS2_EXTENSION ON)
endif()
# Hide automatically generated CTest targets
set_property(GLOBAL PROPERTY CTEST_TARGETS_ADDED 1)
# Fix Windows problems
if (WIN32)
add_definitions(-DNOMINMAX) # http://www.suodenjoki.dk/us/archive/2010/min-max.htm
add_definitions(-D_USE_MATH_DEFINES)
endif()
# External dependencies
add_subdirectory(external)
find_package(CUDAToolkit REQUIRED)
find_program(BIN2C bin2c DOC "Path to the cuda-sdk bin2c executable.")
if (NOT DEFINED ENV{OptiX_INSTALL_DIR})
message(FATAL_ERROR "Required environment variable OptiX_INSTALL_DIR is empty, aborting build")
endif()
# Includes
include_directories(include)
include_directories($ENV{OptiX_INSTALL_DIR}/include)
include_directories(${spdlog_SOURCE_DIR}/include)
# Compile OptiX device programs (pipeline) and embed the binary in a library as a char[]
add_library(optixProgramsPtx OBJECT src/gpu/optixPrograms.cu)
target_include_directories(optixProgramsPtx PRIVATE src include)
set_target_properties(optixProgramsPtx PROPERTIES CUDA_PTX_COMPILATION ON)
add_custom_command(
OUTPUT optixProgramsPtx.c
COMMAND ${BIN2C} -c --padd 0 --type char --name optixProgramsPtx $<TARGET_OBJECTS:optixProgramsPtx> > optixProgramsPtx.c
DEPENDS optixProgramsPtx $<TARGET_OBJECTS:optixProgramsPtx> # Should work with just optixProgramsPtx, but CMake..
VERBATIM)
add_library(optixPrograms optixProgramsPtx.c)
add_library(RobotecGPULidar SHARED
src/api/apiCommon.cpp
src/api/apiCore.cpp
src/Tape.cpp
src/Logger.cpp
src/VArray.cpp
src/Optix.cpp
src/gpu/gaussianNoiseKernels.cu
src/gpu/nodeKernels.cu
src/scene/Scene.cpp
src/scene/Mesh.cpp
src/scene/Entity.cpp
src/scene/Texture.cpp
src/scene/ASBuildScratchpad.cpp
src/graph/Graph.cpp
src/graph/Node.cpp
src/graph/GaussianNoiseAngularHitpointNode.cpp
src/graph/GaussianNoiseAngularRayNode.cpp
src/graph/GaussianNoiseDistanceNode.cpp
src/graph/CompactPointsNode.cpp
src/graph/FormatPointsNode.cpp
src/graph/RaytraceNode.cpp
src/graph/TransformPointsNode.cpp
src/graph/TransformRaysNode.cpp
src/graph/FromArrayPointsNode.cpp
src/graph/FromMat3x4fRaysNode.cpp
src/graph/SetRaysRingIdsRaysNode.cpp
src/graph/SpatialMergePointsNode.cpp
src/graph/TemporalMergePointsNode.cpp
src/graph/YieldPointsNode.cpp
)
set_property(TARGET RobotecGPULidar PROPERTY POSITION_INDEPENDENT_CODE ON)
target_compile_definitions(RobotecGPULidar PUBLIC RGL_BUILD_PCL_EXTENSION=$<BOOL:${RGL_BUILD_PCL_EXTENSION}>)
target_compile_definitions(RobotecGPULidar PUBLIC RGL_BUILD_ROS2_EXTENSION=$<BOOL:${RGL_BUILD_ROS2_EXTENSION}>)
target_compile_definitions(RobotecGPULidar PUBLIC RGL_BUILD_UDP_EXTENSION=0)
if (RGL_BUILD_PCL_EXTENSION)
find_package(PCL 1.12 CONFIG REQUIRED COMPONENTS common io filters visualization)
target_sources(RobotecGPULidar PRIVATE
src/api/apiPcl.cpp
src/graph/DownSamplePointsNode.cpp
src/graph/VisualizePointsNode.cpp
)
target_include_directories(RobotecGPULidar PUBLIC ${PCL_INCLUDE_DIRS})
target_link_directories(RobotecGPULidar PRIVATE ${PCL_LIBRARY_DIRS})
target_link_libraries(RobotecGPULidar PRIVATE ${PCL_LIBRARIES})
endif()
if (RGL_BUILD_ROS2_EXTENSION)
if (NOT $ENV{ROS_DISTRO} STREQUAL "humble")
message(FATAL_ERROR "ROS $ENV{ROS_DISTRO} not supported. Only humble is available.")
endif()
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
target_sources(RobotecGPULidar PRIVATE src/api/apiRos2.cpp src/graph/Ros2PublishPointsNode.cpp)
target_include_directories(RobotecGPULidar PUBLIC ${rclcpp_INCLUDE_DIRS} ${sensor_msgs_INCLUDE_DIRS})
target_link_libraries(RobotecGPULidar PRIVATE ${rclcpp_LIBRARIES} ${sensor_msgs_LIBRARIES})
endif()
target_include_directories(RobotecGPULidar
PUBLIC include
PRIVATE src
)
target_link_libraries(RobotecGPULidar PRIVATE
spdlog
yaml-cpp
optixPrograms
cmake_git_version_tracking
)
target_link_libraries(RobotecGPULidar PUBLIC
CUDA::nvml
CUDA::cudart_static
CUDA::cuda_driver
)
# Create a CMake list with available log levels (rgl_log_level_t)
set(RGL_AVAILABLE_LOG_LEVELS
RGL_LOG_LEVEL_ALL
RGL_LOG_LEVEL_TRACE
RGL_LOG_LEVEL_DEBUG
RGL_LOG_LEVEL_INFO
RGL_LOG_LEVEL_WARN
RGL_LOG_LEVEL_ERROR
RGL_LOG_LEVEL_CRITICAL
RGL_LOG_LEVEL_OFF
)
# Check if RGL_LOG_LEVEL is a valid variable
if (NOT ("RGL_LOG_LEVEL_${RGL_LOG_LEVEL}" IN_LIST RGL_AVAILABLE_LOG_LEVELS))
message(FATAL_ERROR "Incorrect RGL_LOG_LEVEL value: ${RGL_LOG_LEVEL}")
endif()
if (WIN32 AND RGL_AUTO_TAPE_PATH)
message(FATAL_ERROR "(Auto)Tape not supported on Windows")
endif()
# Pass #define-s to RGL compilation
target_compile_definitions(RobotecGPULidar
PUBLIC RGL_LOG_STDOUT=$<BOOL:${RGL_LOG_STDOUT}>
PUBLIC RGL_LOG_FILE="${RGL_LOG_FILE}"
PUBLIC RGL_LOG_LEVEL=RGL_LOG_LEVEL_${RGL_LOG_LEVEL}
PUBLIC RGL_AUTO_TAPE_PATH="${RGL_AUTO_TAPE_PATH}"
)
# Include tests
if (RGL_BUILD_TESTS)
enable_testing()
add_subdirectory(test)
endif()
# Include tools
if (RGL_BUILD_TOOLS)
add_subdirectory(tools)
endif()
# Include ros2_standalone
if(RGL_BUILD_ROS2_EXTENSION_STANDALONE)
add_subdirectory(ros2_standalone)
endif()