123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130 |
- cmake_minimum_required(VERSION 2.8.3)
- project(lvi_sam)
- ######################
- ### Cmake flags
- ######################
- set(CMAKE_BUILD_TYPE "Release")
- set(CMAKE_CXX_FLAGS "-std=c++14")
- 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)
- find_package(RapidJSON)
- ######################
- ### 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}
-
- )
- 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)
- # 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)
|