# ROS Noetic + GTSAM 4.x 환경에서 LIO-SAM 빌드 오류 해결기
이 문서는 Ubuntu 20.04 / ROS Noetic 환경에서 LIO-SAM 패키지를 빌드하는 과정에서 발생했던 에러들을 해결한 과정을 정리한 것입니다. Velog에 정리할 때 바로 활용할 수 있도록, 문제 발생 배경부터 최종 빌드 성공까지의 단계별 작업 흐름을 그대로 담았습니다.
---
## 1. 환경 및 문제 개요
- **운영체제**: Ubuntu 20.04
- **ROS 버전**: Noetic
- **GTSAM 버전**: 4.0.3 (APT로 설치)
- **PCL 버전**: 1.10 (Ubuntu 20.04 기본)
- **OpenCV 버전**: 4.x
- **문제점**
- LIO-SAM을 `catkin_make`(또는 `catkin build`) 했을 때, PCL의 `point_representation.h`에서
```
error: the value of ‘NrDims’ is not usable in a constant expression
```
와 같은 템플릿 인스턴스화 관련 에러가 발생
- OpenCV 헤더가 FLANN(= PCL 내부 의존)와 충돌하면서
```
error: ‘class std::unordered_map<unsigned int, std::vector<unsigned int> >’ has no member named ‘serialize’
```
같은 Boost.Serialization 관련 에러가 발생
위 두 가지 에러가 섞여서, 한 번에 빌드가 완료되지 않았습니다. 아래 내용은 이를 해결하기 위해 수정한 파일들과 설정을 단계별로 정리한 것입니다.
---
## 2. 사전 준비: 설치된 GTSAM 버전 확인
먼저, 시스템에 어떤 GTSAM 버전이 설치되어 있는지 확인합니다. 터미널에 다음 명령어를 입력하세요.
```bash
dpkg -l | grep gtsam
출력 예시:
ii libgtsam-dev 4.0.3-1ubuntu1 amd64 GTSAM library header and config files
ii libgtsam-unstable-dev 4.0.3-1ubuntu1 amd64 GTSAM unstable library header and config files
ii libgtsam-unstable4:amd64 4.0.3-1ubuntu1 amd64 Unstable parts of GTSAM (flann, LSH 등)
ii libgtsam4:amd64 4.0.3-1ubuntu1 amd64 GTSAM Georgia Tech Smoothing and Mapping Library
4.0.3 버전이 설치되어 있음을 확인했습니다.utility.h 수정원본 include/utility.h에는 다음과 같은 이슈가 있었습니다:
OpenCV 헤더 순서 문제
PCL 미리 컴파일된 포인트 타입(PCL_NO_PRECOMPILE) 미사용
PCL_NO_PRECOMPILE 매크로를 정의해야 함이 두 가지를 해결하기 위해 utility.h 맨 상단을 다음과 같이 변경했습니다.
#pragma once
#ifndef _UTILITY_LIDAR_ODOMETRY_H_
#define _UTILITY_LIDAR_ODOMETRY_H_
// ─── 1. PCL 미리 컴파일 비활성화 ──────────────────────────
#define PCL_NO_PRECOMPILE
#define PCL_ONLY_CORE_POINT_TYPES
// ─── 2. Boost.Serialization Include ───────────────────────
#include <boost/serialization/unordered_map.hpp>
// ─── 3. ROS 헤더들 ────────────────────────────────────────
#include <ros/ros.h>
#include <std_msgs/Header.h>
#include <std_msgs/Float64MultiArray.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/NavSatFix.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
// ─── 4. PCL 헤더들 (OpenCV보다 먼저) ──────────────────────
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/impl/search.hpp>
#include <pcl/range_image/range_image.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/common/common.h>
#include <pcl/common/transforms.h>
#include <pcl/registration/icp.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/filter.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/crop_box.h>
#include <pcl_conversions/pcl_conversions.h>
// ─── 5. TF 헤더들 ─────────────────────────────────────────
#include <tf/LinearMath/Quaternion.h>
#include <tf/transform_listener.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
// ─── 6. OpenCV 헤더 (PCL 헤더들 뒤에 포함) ───────────────
#include <opencv2/opencv.hpp>
// ─── 7. STL 및 기타 유틸리티 ─────────────────────────────
#include <vector>
#include <cmath>
#include <algorithm>
#include <queue>
#include <deque>
#include <iostream>
#include <fstream>
#include <ctime>
#include <cfloat>
#include <iterator>
#include <sstream>
#include <string>
#include <limits>
#include <iomanip>
#include <array>
#include <thread>
#include <mutex>
using namespace std;
typedef pcl::PointXYZI PointType;
enum class SensorType { VELODYNE, OUSTER, LIVOX };
// … 이하 생략 (기존 내용 그대로 유지) …
#endif // _UTILITY_LIDAR_ODOMETRY_H_
핵심 요약
#define PCL_NO_PRECOMPILE, #define PCL_ONLY_CORE_POINT_TYPES를 가장 상단에 두어 PCL의 컴파일 방식을 제어<boost/serialization/unordered_map.hpp>를 먼저 포함하여 FLANN(= PCL 내부 의존) 에러를 방지<opencv2/opencv.hpp>는 PCL 헤더 뒤쪽에 위치해야 FLANN–OpenCV 간의 USE_UNORDERED_MAP 충돌을 피할 수 있음CMakeLists.txt 수정다음으로, 패키지 전체 CMake 설정을 Noetic + GTSAM 4.x에 맞게 조정합니다.
주요 변경 사항은 다음과 같습니다:
-std=c++14로 설정find_package(Boost … serialization)로 Boost.Serialization 확인add_definitions(-DPCL_NO_PRECOMPILE -DPCL_ONLY_CORE_POINT_TYPES)를 추가include_directories(...), link_directories(...)에 Boost, GTSAM 경로 포함최종 CMakeLists.txt 예시는 아래와 같습니다.
cmake_minimum_required(VERSION 2.8.3)
project(lio_sam)
# ─── 1. 빌드 타입 & C++ 표준 ──────────────────────────────────
set(CMAKE_BUILD_TYPE "Release")
set(CMAKE_CXX_FLAGS "-std=c++14")
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g -pthread")
# ─── 2. ROS, OpenMP, PCL, OpenCV, GTSAM, Boost 찾기 ───────────
find_package(catkin REQUIRED COMPONENTS
tf
roscpp
rospy
cv_bridge
pcl_conversions
std_msgs
sensor_msgs
geometry_msgs
nav_msgs
message_generation
visualization_msgs
)
find_package(OpenMP REQUIRED)
find_package(PCL REQUIRED QUIET)
find_package(OpenCV REQUIRED QUIET)
find_package(GTSAM REQUIRED QUIET)
find_package(Boost REQUIRED COMPONENTS timer serialization)
# ─── 3. 전처리 매크로 정의 (PCL 최적화) ───────────────────────
add_definitions(-DPCL_NO_PRECOMPILE -DPCL_ONLY_CORE_POINT_TYPES)
# ─── 4. 메시지/서비스 파일 등록 ───────────────────────────────
add_message_files(
DIRECTORY msg
FILES
cloud_info.msg
)
add_service_files(
DIRECTORY srv
FILES
save_map.srv
)
generate_messages(
DEPENDENCIES
geometry_msgs
std_msgs
nav_msgs
sensor_msgs
)
catkin_package(
INCLUDE_DIRS include
DEPENDS PCL GTSAM Boost
CATKIN_DEPENDS
std_msgs
nav_msgs
geometry_msgs
sensor_msgs
message_runtime
message_generation
visualization_msgs
)
# ─── 5. 인클루드 디렉토리 설정 ─────────────────────────────────
include_directories(
include
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${GTSAM_INCLUDE_DIR}
${Boost_INCLUDE_DIRS}
)
# ─── 6. 라이브러리 디렉토리 설정 (링크 디렉토리) ───────────────
link_directories(
${PCL_LIBRARY_DIRS}
${OpenCV_LIBRARY_DIRS}
${GTSAM_LIBRARY_DIRS}
)
####################
## Build targets ##
####################
# 1. Range Image Projection
add_executable(${PROJECT_NAME}_imageProjection src/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}
)
# 2. Feature Association
add_executable(${PROJECT_NAME}_featureExtraction src/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}
)
# 3. Mapping Optimization
add_executable(${PROJECT_NAME}_mapOptmization src/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
Boost::timer
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${OpenCV_LIBRARIES}
${OpenMP_CXX_FLAGS}
gtsam
)
# 4. IMU Preintegration
add_executable(${PROJECT_NAME}_imuPreintegration src/imuPreintegration.cpp)
add_dependencies(${PROJECT_NAME}_imuPreintegration
${catkin_EXPORTED_TARGETS}
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(
${PROJECT_NAME}_imuPreintegration
Boost::timer
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${OpenCV_LIBRARIES}
gtsam
)
주요 포인트
set(CMAKE_CXX_FLAGS "-std=c++14") 으로 C++14 표준 사용add_definitions(-DPCL_NO_PRECOMPILE -DPCL_ONLY_CORE_POINT_TYPES) 로 PCL 템플릿 인스턴스화를 최소화find_package(Boost … serialization) 및 target_link_libraries(... Boost::timer ...) 로 Boost.Serialization을 로드include_directories, link_directories에 GTSAM, Boost 경로를 포함의존성 패키지 설치
이미 ROS Noetic, PCL, OpenCV, GTSAM, Boost 등이 설치되어 있음을 가정합니다.
부족한 패키지가 있다면 아래 명령어로 설치하세요:
sudo apt update
sudo apt install -y \
ros-noetic-pcl-ros \
ros-noetic-cv-bridge \
libgtsam-dev \
libboost-timer-dev \
libboost-serialization-dev
(버전 이름이 변경될 수 있으니, apt search gtsam 등을 통해 확인)
워크스페이스 초기화 및 클린 빌드
cd ~/ouster_ws
# (선택 사항) 이전 빌드 결과물을 모두 지우기
catkin clean # catkin_tools 사용 시
rm -rf build/ devel/
빌드
cd ~/ouster_ws
catkin_make -DCMAKE_BUILD_TYPE=Release
또는 catkin build 사용 시:
catkin build lio_sam
환경 변수 소스
source ~/ouster_ws/devel/setup.bash
정상적으로 빌드되면, devel/lib/lio_sam/ 디렉터리 아래에 다음 실행 파일들이 생성됩니다:
lio_sam_imageProjectionlio_sam_featureExtractionlio_sam_mapOptmizationlio_sam_imuPreintegration# 예시: imageProjection 노드 실행
roslaunch lio_sam run.launch
(실제 런치 파일 이름 및 내용은 사용 중인 LIO-SAM 버전에 따라 다를 수 있습니다.)
문제 원인
NrDims가 상수식이 못 된다는 에러핵심 해결책
utility.h 최상단에 #define PCL_NO_PRECOMPILE과 #define PCL_ONLY_CORE_POINT_TYPES를 선언<opencv2/opencv.hpp>보다 먼저 인클루드CMakeLists.txt에서 C++ 표준을 C++14로 변경find_package(Boost … serialization) 및 target_link_libraries(... Boost::timer ...) 설정 추가결과
utility.h 인클루드 순서 문제와 C++ 표준 불일치가 가장 큰 장벽이었음