
원형 패턴을 사용한 강건한 6-DoF추정을 위한 LiDAR 데이터 처리 알고리즘
CopyrightⓒKROS
Abstract
Accurate LiDAR(Light Detection and Ranging) data processing is essential for precise sensor calibration and reliable 3D perception in applications such as autonomous driving and robotics. Traditional methods often rely on artificial targets like circular patterns for 6-DoF estimation due to their ability to precisely detect geometric features. However, few studies focus on improving the accuracy of raw LiDAR data through preprocessing, leaving unresolved issues related to LiDAR’s inherent limitations. To address these challenges, we propose a novel LiDAR data processing algorithm that improves robustness and 6-DoF estimation accuracy. It enhances target plane detection accuracy by using perspective projection, accounting for LiDAR’s range direction errors. We also resolve data bias from scanning patterns using CDR(Centroid Distance Ratio) and directional variance, allowing for the extraction of reliable boundary points. Experimental results demonstrate significantly lower RMSE compared to existing techniques, highlighting the enhanced precision and robustness of our approach. Furthermore, our method achieves higher accuracy in 6-DoF estimation compared to traditional methods.
Keywords:
Calibration, LiDAR, Pose Estimation1. 서 론
LiDAR (Light Detection and Ranging) 센서는 거리 정보를 직접적으로 얻을 수 있다는 점에서 로보틱스, 자율주행 분야에서 많이 활용된다. LiDAR는 다른 비전 센서와 융합하여 사용되는 경우가 많으며, 특히 카메라와 함께 사용되는 경우가 많다. LiDAR-카메라 퓨전을 통해 단일 영상에서는 얻을 수 없는 깊이 정보를 얻을 수 있으며, 색이 없는 LiDAR 데이터에 색상이 입혀진 point cloud 데이터를 얻을 수 있게 된다. 이 경우 센서 간의 상대적인 위치 정보를 알아내는 calibration 작업이 필수적이다. Calibration이 이루어져야만 LiDAR의 거리 정보를 카메라에서 사용하거나, 카메라의 색상 정보를 LiDAR에서 사용할 수 있게 된다.
이처럼 LiDAR-카메라 calibration은 중요한 작업이지만, 두 센서가 제공하는 정보가 각각 거리 정보와 색상 정보라는 점에서 calibration이 쉽지 않다. 그렇기에 두 센서에서 모두 인식 가능하도록 특별하게 제작된 Target을 이용하여 calibration을 진행하는 Target-based 방법은 Target-less 방법에 비해 높은 정확도를 가진다. 그 중에서도 원형 패턴을 이용한 타겟을 활용하는 방법은 패턴의 경계점을 더 많이 검출할 수 있다는 점에서 체커보드 형태 보드보다 더 정밀한 6-DoF 추정을 가능하게 한다[1]. 기존 연구들은 target의 종류와[2,3], LiDAR에서 추출된 point cloud와 카메라 이미지에서 얻은 특징점과의 정합 방식에 초점을 맞추고 있다[4,5]. 반면, LiDAR에서 얻은 raw 데이터를 전처리를 통해 정확도를 향상시키는 방법에 대한 연구는 상대적으로 부족하다. 이러한 연구의 부족은 Target-based calibration에서의 오차를 증가시킨다. LiDAR-카메라 캘리브레이션에서 발생하는 오차는 일반적으로 1~3 cm로 보고되며[6-8], 여기에 사용되는 카메라 캘리브레이션 방법들의 정밀도가 평균 5 mm 이내로 매우 높은 것을 고려할 때[9,10], 이러한 캘리브레이션 오차의 주요 원인은 LiDAR에서 기인한다고 볼 수 있다. 따라서 LiDAR 캘리브레이션의 정밀도를 높이는 것은 LiDAR-카메라 캘리브레이션의 정확도를 향상시키는 데 있어서 중요한 연구 과제이다.
LiDAR로 취득한 raw 데이터는 크게 두가지 한계점을 갖고 있다([Fig. 1(a)]). LiDAR로부터 나오는 빛의 방향은 정확하지만 해당 방향에서 얻어지는 거리정보는 노이즈로 인해 실제 값과 오차가 존재한다. 또한 LiDAR의 scanning 패턴에 따라 특정방향으로만 정보량이 집중되는 한계가 있다(예를 들어, 스피닝 LiDAR의 경우 세로방향의 데이터 해상도가 가로방향에 비해 크게 떨어진다). 보드판이 기울어질수록 이런 문제는 더욱 심화되며[6-8] 이러한 LiDAR센서의 물리적 한계는 정확한 calibration이 필요한 로보틱스 응용 분야에서 중요한 문제로 부각된다[11].
Overview of our research contributions: (a) highlights the inherent limitations of LiDAR point cloud data, and (b) presents the key methods of the noise-robust LiDAR data processing approach we have developed
본 연구는 이와 같은 LiDAR의 센서의 특징을 이해하고 그 한계를 극복하여 정확한 6-DoF 추정을 수행하는데 초점을 맞추고 있다[Fig. 1(b)]. 첫째, Target board가 속해 있는 평면을 검출하는 과정에서 LiDAR센서가 갖는 거리방향 노이즈를 고려하여 PCA 분석과 perspective projection을 활용한다. 이 방법은 정확한 plane을 얻을 수 있게 하며 이후 진행되는 과정을 3차원이 아닌 2차원으로 이동시켜 변수들의 자유도를 낮추는 장점이 있다. 둘째, CDR (Centroid Distance Ratio)과 Directional variance 개념을 도입하여 패턴 경계점의 주변 점들의 분포를 분석함으로써 신뢰도 있는 경계점만 추출한다. 이는 LiDAR의 스캐닝 패턴에 따른 데이터의 불균형 문제를 해결한다. 결론적으로, 우리는 LiDAR calibration을 넘어서 LiDAR 데이터의 특성을 효과적으로 해석하여 외부 환경 노이즈와 센서 노이즈를 극복하는 전처리 방법을 제안한다. 본 논문에서 제안하는 논점은 다음과 같다.
- - LiDAR의 데이터 취득 방식과 거리방향 오차를 고려한 perspective projection을 통해 평면 사영 정확도를 상승시켰다.
- - LiDAR 스캐닝 패턴에서 기인하는 데이터 쏠림 현상을 주변 점들의 분포를 고려하는 CDR, directional variance를 통해 해결하여 신뢰도 있는 경계점을 추출하였다.
- - 다양한 실험을 통해 원형 패턴 경계점 추출의 정확도와 6-DoF 추정 정확도가 기존 방법들을 능가함을 확인하였다.
2. 선행 연구 조사
2.1 LiDAR기반 Target-based Calibration
LiDAR는 레이저 펄스를 이용해 주변 환경의 거리를 측정하고 이를 기반으로 3D point cloud를 생성하는 센서로 다른 센서들과 함께 활용하기 위해서는 calibration이 필요하다. Target-based calibration 방법은 특수한 형태의 물체가 센서에 관찰된 형태를 통해 센서간 상대적 위치를 추정하는 방식으로, 자율주행차와 로봇플랫폼에서 활발히 연구되어 왔다. 평면 타겟이나 원형 타겟을 사용하는 방식은 target-less 또는 odometry 기반의 calibration 방법에 비해 더 높은 정확도를 제공하는데, 이는 타겟 기반 방식이 명확한 참조 지점을 제공하여 노이즈나 환경 변화에 민감하지 않고 더욱 일관된 보정 결과를 도출할 수 있기 때문이다.
LiDAR 기반 calibration에서 주로 사용되는 target들은 평면 체커보드[12] 또는 원형 패턴[1] 등과 같은 특정 기하학적 특징을 가지며, 이를 통해 LiDAR의 point cloud 데이터와 타겟의 기하학적 특성을 매칭시키는 방식이다. Calibration을 위해 타겟의 모든 점을 사용하기도 하며 [13], 경계선을 사용하기도 한다[14]. 전통적인 방법 외에도 삼각형 모양의 판[3]이나 구형 목표물[15]과 같이 특별히 새롭게 제작된 타겟의 기하학적 특징을 사용해 calibration을 진행하기도 한다.
그러나, 이러한 target-based 방법에는 몇 가지 한계가 존재한다. 저해상도 LIDAR을 사용하는 경우, 충분한 포인트가 제공되지 않아 정확도가 떨어질 수 있다. 또한, LiDAR 자체의 데이터에서 발생하는 노이즈로 인해 타겟의 기하학적 특성을 추출하는 단계에서 오차가 발생할 수 있다. 이를 개선하기 위해 원형 패턴을 사용하려는 시도가 있었다. 주로 체커보드나 다각형 보드를 사용한 calibration 방식이 많았지만, 원형 패턴을 사용하는 방식은 비슷한 크기의 다른 패턴을 사용하는 방식에 비해 수평 및 수직 위치를 명확히 감지할 수 있어, 다각형 보드를 사용하는 방식에 비해 6-DoF 추정에서 더 높은 정밀도를 제공한다[1].
그러나 원형 패턴을 사용하는 기존 방식에도 몇 가지 한계가 존재한다. 원형 패턴 방식은 경계점을 더 많이 뽑을 수 있지만 이러한 경계점들이 외부환경이나 LiDAR 자체의 노이즈로 인해 정확성이 떨어진다는 문제점이 있다[6-8]. 특히, 보드판이 많이 기울어진 경우, 점들이 평면에 사영되는 과정에서 생기는 오차가 커지기 때문에 원형 패턴 감지가 어려워질 수 있다[16]. 특히, 기존 방식들은 단일 시점의 데이터를 기반으로 보드판의 위치를 추정하기 때문에, 노이즈에 더욱 취약해져 정밀한 calibration을 수행하는 데 한계가 있다. 또한, 기존 방식들은 단일 시점의 데이터만을 사용하여 보드판의 위치를 추정하기 때문에, point cloud 밀도가 낮아져 각 점의 noise가 결과값에 미치는 영향이 커지고, 이로 인해 정밀한 보정 수행에 한계가 있다.
2.2 Target-less 및 Odometry 기반 Calibration
최근 연구는 타겟을 사용하지 않는 target-less calibration 방법으로 확장되고 있다. 이러한 접근 방식은 자연환경에서 특징 데이터를 이용해 센서 간의 calibration을 자동화할 수 있다는 장점을 가진다[17]. 특히 LiDAR와 카메라의 상대적 자세를 타겟 없이 자동으로 추정할 수 있어 많은 관심을 받고 있다.
Target-less 방법은 인공적인 타겟을 사용할 필요가 없기 때문에, 실내 및 실외 환경에서 유연하게 calibration을 수행할 수 있다. 그러나 실외 환경에서는 복잡한 배경과 장애물로 인해 특징들을 안정적으로 감지하기 어려우며, 그 결과 보정의 정확도가 떨어진다[18]. 또한, 지면 평면이나 도로 정보와 같은 환경적 요소를 활용하여 카메라와 LiDAR 간의 calibration을 수행하는 연구도 있지만[19,20], 운동 추정 오류에 민감하며 환경 조건에 따른 제한이 필요하다. 따라서 이 방법은 다양한 환경에서의 활용성에 한계가 있으며, 특정 상황에서만 유효하다.
Odometry 기반 calibration은 차량이나 로봇의 이동 경로를 추적하여 센서 간의 calibration을 수행하는 방법이다. LiDAR와 카메라 간의 변환을 차량의 이동 데이터를 기반으로 추정하며, 자율주행 차량 및 로봇 플랫폼에서 주로 사용된다. SLAM(동시적 위치추정 및 지도작성)등에 주로 활용되며, 이 방식은 이동 경로 데이터를 이용해 두 센서 간의 상대적 위치와 자세를 계산한다[21].
그러나 odometry 기반의 calibration은 각 센서에서 얻은 odometry 데이터가 모두 정확해야 한다는 전제 조건이 필요하기 때문에, 환경이나 센서 종류에 따라 그 성능이 달라질 수 있는 만큼 노이즈나 환경조건에 민감하여 자율주행차와 같이 높은 정확도를 요구하는 시스템에서는 한계를 보일 수 있다[22]. 특히, 센서의 해상도나 데이터 밀도가 낮으면 calibration정확도가 떨어질 수 있다[23].
3. 연구 방법
3.1 Notation and Coordinates
추정하고자 하는 상태를 정의하기 앞서, 사용하는 좌표계와 그 변환 관계, 표시 방법을 정리할 필요가 있다. 본 논문에서는 두 개의 좌표계를 사용한다.
- - Calibration board를 기준으로 한 보드 좌표계 (•)B
- - LiDAR를 기준으로 한 LiDAR좌표계 (•)L
이 두 좌표계 사이의 관계는 6개의 자유도(degrees of freedom, DOF)로 정의되며, 그 파라미터는 축에 대한 회전 r과 축 방향 평행이동 t로 다음과 같이 표현된다.
| (1) |
이 파라미터들은 다시 두 좌표계 간의 SE3 행렬 T를 정의하며, 이를 통해 다음과 같은 변환 관계를 나타낼 수 있다. L는 4×4 행렬이며 PL는 LiDAR 좌표계상의 3D point cloud 좌표에 1을 붙여 만든 1×4벡터, PB는 보드판 좌표계상의 point cloud 좌표에 1을 붙여 만든 1×4벡터이다. 이때 보드판 좌표계는 x, y좌표축을 보드판 상의 축, z 좌표축은 보드판과 수직한 축으로 잡았다.
| (2) |
3.2 Data Accumulation
데이터 분석의 정확성을 높이고 noise의 영향을 줄이기 위해, N개의 LiDAR 장면을 중첩하여 높은 point cloud 밀도를 확보함으로써 각 점의 노이즈가 결과값에 미치는 영향을 최소화한다. 이렇게 중첩된 scene들은 LiDAR 좌표계 (•)L를 기준으로 한 3D point cloud 0PL을 생성한다. 0PL은 [Fig. 2]에 나타나 있으며, 이후의 과정 또한 [Fig. 2]에 정리되어 있다.
3.3 Plane Clustering
먼저 0PL에서 타겟이 위치하는 범위의 데이터들을 대략적으로 분리한 후, 분리한 point cloud에 DBSCAN[24]을 적용한다. 이렇게 만들어진 cluster들에 PCA분석을 수행하여 가장 평면에 가까운 cluster를 찾는다. 평면에 가까운 point cloud에 PCA 분석을 진행하면 1st, 2nd eigenvalue와 3rd eigenvalue가 큰 차이가 나게 된다. 이를 이용해 가장 평면에 가까운 point cloud 1PL을 분리한다.
분리된 1PL을 사용하여 LiDAR 좌표계 상에서 calibration board의 평면의 방정식을 찾는다. 1PL의 PCA분석 결과로 평면의 방정식을 구하게 되면 noise의 영향이 강하게 나타나므로, noise를 먼저 처리해야 한다. 이를 위해 1PL에 RANSAC[25]을 적용하여 point cloud 2PL를 만들고, 2PL에 대해 PCA분석을 다시 수행한다. 충분한 scene을 중첩해 0PL을 만들었기 때문에, range error들이 포함된 점들이 보드판을 중심으로 분포하게 된다. 따라서 PCA분석을 통해 정확한 평면을 구할 수 있다. 이렇게 구한 PCA 결과의 3rd eigenvector에 수직이고, 2PL의 평균점을 지나는 평면 π를 찾는다. 2PL과 π의 형태는 [Fig. 2]에서 확인할 수 있다.
3.4 Perspective Projection
찾은 평면 π에 2PL의 점들을 사영한다. 이때, 일반적인 사영 방법을 사용하지 않고, perspective projection을 사용한다. 이는 원점과 대상 점을 지나는 직선이 평면과 만나는 점으로 사영하는 방식이다.
기존의 방법들은 평면을 찾고 그 점들을 찾은 평면에 수직으로 사영하는 방법을 선택하였다[6,16,26]. 그러나 LiDAR의 특성상 range방향의 오차가 존재하고, 이는 평면 π에 수직으로 분포하지 않는다. 그렇기 때문에 이를 수직으로 사영하면 range 오차로 인해 원형 패턴이 왜곡되어 calibration결과에 오차가 발생한다.
이는 [Fig. 3]에서 확인할 수 있다. 우리는 중첩된 scene들을 거리방향으로 사영해 거리방향 오차를 제거하여 calibration의 정확도를 높였다. π에 2PL을 perspective projection을 사용하여, 사영이 완료된 point cloud 3PL을 얻는다.
3.5 Circle Detection
다음으로 3PL에서 원형 패턴을 찾는다. 먼저 원형 패턴을 찾기 위해 원의 경계를 찾아야 한다.
우리는 사영된 점들에서 경계점들을 추출하기 위해, 2차원 point cloud 상에서 경계점를 추출하는 두 가지 factor를 도입했다. 경계점에서는 주변 점들의 분포가 편향되어 있다는 특성을 이용하여, 두 factor는 기준점 주위의 점들이 얼마나 편향되어 있는지 나타내도록 선택하였다.
각 점에서 이웃의 중심(centroid)까지의 거리와 이웃 간의 평균 거리의 비율을 계산하는 지표인 CDR을 정의하였다. Point cloud P 안의 한 점의 위치벡터 p에 대해, p를 기준으로 한 반경 내에서 유효한 이웃들의 벡터 vi = pi - p가 n개 존재할 때 CDR은 다음과 같이 정의된다.
| (3) |
CDR을 계산하는 과정을 그림으로 표현하면 [Fig. 4(a)]와 같다. CDR은 pi와 반경 내의 점들의 평균점 간의 거리가, pi와 점들 간의 거리의 평균과 얼마나 차이가 나는지 계산하는 지표이다. 점들이 완전히 균일하게 분포할 때 CDR은 0, 완전히 편향되어 있을 때 1의 값을 가진다. 경계점에서는 주변 점들이 편향되어 CDR이 크게 나타나므로, CDR이 일정 이상인 점들만 경계점으로 선택한다.
LiDAR의 특성상 수직 방향으로 점들의 분포가 세밀하지 않기 때문에, 수평 방향과 접하는 원의 경계점들은 위치의 불확실성이 높게 나타난다. 따라서 이 점들은 경계점에서 제외하는 것이 정확도가 높다. 수직 방향으로 점들의 분포가 세밀하지 않다는 점을 이용해, [Fig. 1(b)]에서와 같이 CDR을 계산하는 반경을 적절히 조절하면 판별의 기준이 되는 점의 수평 방향 점들만 선택하여 분석할 수 있다.
[Fig. 1(b)]에서 수평 방향과 접하는 원의 경계점들은 수평 방향 점들만으로 CDR을 평가할 경우 점들이 좌우 방향으로 균일하게 분포하고 있으므로 CDR이 낮게 나타난다. 따라서 이 과정을 통해 경계점에서 제외할 수 있으며, 위치 정확성이 높은 점들만 경계로 선택할 수 있다.
벡터 vi의 normalized vector 에 대해 Directional variance는 다음과 같이 정의된다.
| (4) |
Directional variance를 계산하는 과정을 그림으로 표현하면 [Fig. 4(b)]와 같다. 점들이 완전히 균일하게 분포할 때 은 1, 완전히 편향되어 있을 때 0의 값을 가진다. 점들이 편향되어 있을수록 은 작게 나타나고, 이 일정 이하인 점들 만을 경계점으로 선택한다. Directional variance 역시 CDR과 마찬가지로 수평 방향과 접하는 원의 경계점들의 주변에 점들이 좌우 방향으로 균일하게 분포하므로 위치 정확성이 높은 점들만 경계로 선택할 수 있다.
이상의 방법으로 경계점들을 추출한 후, circle detection에 방해가 되는 보드의 가장자리들을 제거한다. 3PL의 중심점에서 3PL에 PCA분석을 적용한 주축의 방향으로 일정 거리 이상 떨어진 좌표에 해당하는 점들을 경계점에서 제외한다. 이상의 방법으로, 경계점들로 이루어진 point cloud 4PL을 얻는다.
3.6 Center Detection
마지막으로, 4PL에서 RANSAC을 기반으로 한 circle detection algorithm을 사용하여 각 원들에 속하는 점들을 분리해 낸다. 현재 4PL의 점들은 3차원 상의 점으로 표현되어 있으나, RANSAC알고리즘의 계산 효율을 높이기 위해, 4PL의 점들이 2차원 평면 π상에 있다는 정보를 활용하여 점들의 좌표를 임의의 보드판 좌표계 상에서의 2차원 좌표 로 변환한다. 이 변환을 수행하는 4×4 SE3 행렬을 이라 하며, 변환 결과는 로 나타낼 수 있다. 여기서 point cloud 는 상에서 표현된 점들이며, 1×4벡터로 나타나지만 z좌표는 0이므로, 이를 1×3벡터로 나타내기로 한다.
원 검출을 위해, 먼저 원을 정의할 수 있는 세 개의 점을 선택하여 원을 설정하고, 그 원의 경계를 기준으로 일정한 거리를 threshold로 설정한다. 이 안에 속하는 점들을 원에 포함되는 점으로 간주하고, 포함되는 점들이 가장 많은 원을 최종적으로 선택한다. 이때 원을 구성하는 세 개의 점을 선택할 하나의 기준 점을 먼저 선택하고, 나머지 두 점은 기준 점과 일정 거리 내에 있는 점들 중에서 선택하도록 제약을 둔다. 이러한 방식은 계산 효율성을 높이고, 검출 성능을 개선할 수 있다.
이렇게 분리해 낸 원의 경계점들 , ⋯에 대해, 반지름이 r인 원의 중심 를 아래의 방정식으로부터 구한다.
| (5) |
이상의 과정을 원의 개수만큼 반복해, 구한 각 원들의 중심으로 이루어진 point cloud 5PL을 얻는다.
3.7 6-DoF Estimation
앞선 방법으로 구한 원형 패턴의 중심 를 정확한 보드판 좌표계 B상의 점들로 변환시키는 SE2 행렬 을 구해야 한다. 보드판 좌표계 상의 점 의 z축 좌표는 0이므로 2차원상에서 계산이 가능하며 x, y축 방향 이동거리 tx, ty와 x, y축의 회전각 θ가 최적화해야 하는 optimization variables가 된다. 상의 점들 과 5PB상의 점들 간의 관계를 식으로 나타내면 아래와 같다.
| (6) |
5PB상의 점의 좌표와 실제 보드판 좌표계상의 원의 중심점 좌표((ground truth value, (XBi, YBi))) 간의 거리 차이 제곱의 합 오차를 최소화하는 방법으로 (tx, ty, θ) 세 optimization variables값을 조정한다. 최적화 함수는 아래와 같다.
| (7) |
n은 총 사용된 원 중심의 개수로 본 연구에서는 6개를 사용하였다. Least square은 Ceres Solver[27]을 사용하여 풀었으며 구한 optimization variables의 값들을 대입해 SE2행렬 를 구해낸다. Z축이 포함되도록 행렬을 4×4 행렬로 확장시킨 SE3 행렬을 라 하자. 그러면 결과적인 보드판의 SE3 행렬 TLB는 다음과 같이 구해진다.
| (8) |
4. 실험 및 결과
본 실험은 LiDAR 데이터를 활용하여 원형 패턴의 경계점 추출 정확도와 6-DoF (6 Degrees of Freedom) 추정 정확도를 평가하기 위해 설계되었다. 특히, Range 방향 오차와 보드 기울기가 큰 상황에서도 높은 정확도를 유지할 수 있는 방법을 통해 기존 방식들과 비교하여 원형 패턴 경계점을 추출하고, 타겟 보드의 6-DoF를 추정하여 그 성능을 입증하고자 하였다.
4.1 원형 패턴 경계점 추출의 정확성
기존 알고리즘들[1,6-8,16,26]이 동일한 방식으로 원형 패턴의 경계점을 추출하므로, [16] 논문을 기준으로 하여 경계점 추출 정확성을 비교하는 실험을 진행하였다. Ouster 사의 OS64를 사용하여 12개의 원형 구멍이 뚫린 직사각형 판에서 원형 경계점을 검출했다. 각각의 알고리즘에서 2차원 원형 패턴 경계점 4PL를 추출해 낸 후, 보드판의 중심을 원점으로 하는 좌표계 B′′에 실제 원의 경계면을 표시하는 2차원 point cloud 을 정합하였다. 평가 지표는 RMSE로 설정했다. n개의 점으로 구성된 4PB안의 한 점 4pi와 가장 가까이 있는 안의 점 gtpi에 대해 RMSE는 다음과 같이 구한다.
| (9) |
실험 결과는 다음의 [Table 1]과 같다. LiDAR의 range방향에 대한 기울기가 있을 때, 기존의 알고리즘에 비해 낮은 RMSE 값을 가지는 것을 확인할 수 있다. 또한 각도를 크게 할수록 RMSE의 차이가 크게 나타났다. 이를 통해 수직 사영으로 range 방향 오차가 포함된 값이 평면으로 사영되어 경계점의 정확성을 떨어뜨렸음을 확인할 수 있다.
![[Table 1]](../img/npr_tablethum.jpg)
Circle pattern segmentation precision test The RMSE results of the circular pattern measured while tilting the board at various angles. Our method outperformed the comparative method, especially in tilted situations
오차의 영향으로 인한 원형 패턴의 왜곡은 [Fig. 5]에서 시각적으로 확인할 수 있다. range 방향에 수직일 때의 오차는 LiDAR 센서 자체의 오차에 기인한 것이다. Ouster 사에서 공개한 OS64의 resolution은 약 0.7° (512 channel for 360°)이며, 따라서 타겟 거리를 약 1 m로 설정했을 때 오차 범위는 12 mm이다. 수직 방향에서의 RMSE가 이 값의 절반인 것은 수직일 때의 오차가 LiDAR 자체의 오차에서 기인한 것임을 뒷받침한다.
The visualized result of (a) our method and (b) comparative method, in circle pattern segmentation precision test with 40°of tilted angle. The red dots are detected circle boundaries. The green circles are PgtB''
우리의 알고리즘에서도 range 방향에 대한 각도를 크게 했을 때 RMSE가 증가하는 결과가 나타났다. 그러나 이는 prospective projection이 range error를 보정하지 못하였기 때문이 아니라, LiDAR 센서의 한계 때문이다. 같은 resolution error에 대한 보드판 위치 상에서의 오차는, range 방향에 대한 보드판의 각도가 클수록 커진다. 따라서 각도를 크게 했을 때 우리 알고리즘의 오차가 커진 것은 LiDAR센서 자체의 한계에서 기인한 것이다.
4.2 실제 원형패턴 타겟의 6-DoF 정확도
LiDAR로 수집한 point cloud를 이용해 실제 원형패턴 타겟의 6-DoF를 측정하고 오차를 평가했다. OS64 LiDAR로 9개의 서로 다른 위치에 둔 타겟의 point cloud를 얻었으며 6-DoF를 구해내 calibration정확도를 평가하였다. 얻어낸 6-DoF정보의 정확성을 평가하기 위해 각 타겟 위치의 ground truth value가 필요하다. 이러한 타겟간 상대적인 자세에 대한 GT값은 Opti Track 모션 캡쳐 시스템을 통해 얻었다. TLti는 i번째 타겟 좌표를 LiDAR좌표에서 본 SE(3)행렬이며, Tmoi는 i번째 물체 좌표를 모션 캡쳐 시스템상에서 본 SE(3)행렬이다. 물체의 프레임은 타겟 평면에 부착된 프레임이지만, 모션 캡쳐 시스템은 타겟에 대해 별도의 좌표계를 정의하므로 두 프레임은 동일하지 않다([Fig. 6(a)] 참조).
Experiment environment. (a) We used motion capture system to get the ground truth of the 6-DoF of the target. TmLTLt=TmoTot stands. (b) Positions and direction of normal vectors of the targets determined in the experiment based on our method, with the LiDAR position at (0,0,0) as the reference point
좌표변환 행렬 Tot 및 TmL없이 상대적인 자세를 직접 평 가하는 것은 불가능하다. 따라서 우리는 먼저 변환 행렬을 계산했으며 최종 오차는 아래와 같이 정의된다.
| (10) |
여기서 , 는 추정된 값이다. Ceres solver을 이용해 error의 rotation 성분과 translation성분의 제곱합이 최소가 되도록 하는 , 를 추정해 오차를 구하였다.
정확성 비교를 위해 Open3D라이브러리 방법과 기존 논문[16]의 방법을 가져와 비교하였다. Open3D 라이브러리 방법은 카메라 이미지와 LiDAR 데이터를 정렬해 6-DoF를 찾는다. 그러나 이 방식에서는 LiDAR와 보드 간의 6-DoF를 알 수 없어 비교가 불가능하다. 비교를 위해 우리는 카메라 이미지가 아닌 원점에 놓인 보드 point cloud 데이터와 정렬하여 LiDAR와 보드 간의 6-DoF를 바로 구했다. 기존 논문의 방법은 한 point cloud scene의 정보만 사용하는 반면 우리의 연구는 여러 scene을 중첩시켜 데이터로 활용한다. 따라서 중첩된 scene의 수만큼 6-DoF를 계산한 후 평균을 내어 사용된 데이터 양의 형평성을 맞추었다. 우리는 6scene을 중첩하였기 때문에 5개의 6-DoF정보를 평균 내었고 비교 논문은 30개의 정보를 평균 내어 비교하였다.
보드판을 다양한 위치와 큰 각도를 포함한 다양한 각도로 배치해 실험을 진행하였다. [Fig. 6(b)]는 LiDAR 위치 (0,0,0)를 기준으로 각 보드판 위치와 보드판 평면의 법선 벡터의 방향을 나타낸다. 실험 결과는 [Table 2]에 정리되어 있다. 기울어진 보드판 데이터를 포함한 결과에서, 우리의 방법이 rotation과 translation error 모두에서 가장 뛰어난 성능을 보였다.
5. 결 론
본 연구에서는 LiDAR 기반의 6-DoF 추정을 위한 새로운 알고리즘을 제안하여, 기존 원형 패턴 보정 방식에서 발생하는 노이즈 및 정확도 저하 문제를 해결하였다. 제안된 알고리즘은 scene 축적을 통한 LiDAR의 데이터 취득 방식과 거리방향 오차를 고려한 perspective projection을 통해 평면 사영의 정확도를 높였으며, 스캐닝 패턴으로 인한 데이터 쏠림 현상은 CDR과 directional variance를 이용해 해결하여 신뢰성 있는 경계점을 추출하였다. 실험을 통해 기존 방법들보다 우수한 성능을 입증하였으며, 특히 기존 사영 방식의 취약점인 range error를 perspective projection을 통해 보정할 수 있어 원형 패턴의 정확성 면에서 높은 성능을 보였다. 따라서 본 연구는 노이즈에 강건하고, 타겟 pose에 영향을 받지 않는 신뢰도 높은 6-DoF 추정을 가능하게 하는 LiDAR 센서 보정 방식을 제시하였으며, 정밀한 센서 calibration 작업에 중요한 기여를 할 수 있을 것으로 기대된다.
Acknowledgments
This work was supported by the Technology Innovation Program (1415187329, 20024355, Development of autonomous driving connectivity technology based on sensor-infrastructure cooperation) funded By the Ministry of Trade, Industry & Energy (MOTIE, Korea).
References
- M. Velas, M. Spanel, Z. Materna, and A. Herout, “Calibration of RGB camera with Velodyne LiDAR,” 21st International Conference on Computer Graphics, Visualization and Computer Vision 2013, Pilsen, Czech, pp. 135-144, 2014, [Online], https://dspace.zcu.cz/items/9f0f42d2-518f-4266-8467-deeda1ef7655/full, .
-
Z. Huang, X. Zhang, A. Garcia, and X. Huang, “A novel, efficient and accurate method for lidar camera calibration,” 2024 IEEE International Conference on Robotics and Automation (ICRA), Yokohama, Japan, pp. 14513-14519, 2024.
[https://doi.org/10.1109/ICRA57147.2024.10611162]
-
X. Xu, L. Zhang, J. Yang, C. Liu, Y. Xiong, M. Luo, Z. Tan, and B. Liu, “LiDAR–camera calibration method based on ranging statistical characteristics and improved RANSAC algorithm,” Robotics and Autonomous Systems, vol. 141, Jul., 2021.
[https://doi.org/10.1016/j.robot.2021.103776]
-
Y. Xie, L. Deng, T. Sun, Y. Fu, J. Li, X. Cui, H. Yin, S. Deng, J. Xiao, and B. Chen, “A4LidarTag: Depth-Based Fiducial Marker for Extrinsic Calibration of Solid-State Lidar and Camera,” IEEE Robotics and Automation Letters, vol. 7, no. 3, pp. 6487-6494, Jul., 2022.
[https://doi.org/10.1109/LRA.2022.3173033]
-
D. Tsai, S. Worrall, M. Shan, A. Lohr, and E. Nebot, “Optimising the selection of samples for robust lidar camera calibration,” 2021 IEEE Intelligent Transportation Systems Conference (ITSC), Indianapolis, USA, pp. 2631-2638, 2021.
[https://doi.org/10.1109/ITSC48978.2021.9564700]
-
J. Domhof, J. F. P. Kooij, and D. M. Gavrila, “An Extrinsic Calibration Tool for Radar, Camera and Lidar,” 2019 IEEE International Conference on Robotics and Automation (ICRA), Montreal, Canada, pp. 8107-8113, 2019.
[https://doi.org/10.1109/ICRA.2019.8794186]
-
C. Guindel, J. Beltrán, D. Martín, and F. García, “Automatic extrinsic calibration for lidar-stereo vehicle sensor setups,” 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), Yokohama, Japan, pp. 1-6, 2017.
[https://doi.org/10.1109/ITSC.2017.8317829]
-
J. Levinson and S. Thrun, “Automatic Online Calibration of Cameras and Lasers,” Robotics: science and systems, Jun., 2013.
[https://doi.org/10.15607/RSS.2013.IX.029]
-
Q. Zhang and R. Pless, “Extrinsic calibration of a camera and laser range finder (improves camera calibration),” 2004 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Sendai, Japan, pp. 2301-2306, 2004.
[https://doi.org/10.1109/IROS.2004.1389752]
-
C. Song, J. Shin, M.-H. Jeon, J. Lim, and A. Kim, “Unbiased Estimator for Distorted Conics in Camera Calibration,” 2024 IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR), Seattle, USA, pp. 373-381, 2024.
[https://doi.org/10.1109/CVPR52733.2024.00043]
-
Y. Zhou, T. Han, Q. Nie, Y. Zhu, M. Li, N. Bian, and Z. Li, “Adaptive Point-Line Fusion: A Targetless LiDAR–Camera Calibration Method with Scheme Selection for Autonomous Driving,” Sensors, vol. 24, no. 4, Feb., 2024.
[https://doi.org/10.3390/s24041127]
-
A. Geiger, F. Moosmann, Ö. Car, and B. Schuster, “Automatic camera and range sensor calibration using a single shot,” 2012 IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, pp. 3936-3943, 2012.
[https://doi.org/10.1109/ICRA.2012.6224570]
-
Z. Chai, Y. Sun, and Z. Xiong, “A novel method for LiDAR camera calibration by plane fitting,” 2018 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Auckland, New Zealand, pp. 286-291, 2018.
[https://doi.org/10.1109/AIM.2018.8452339]
-
Y. Lyu, L. Bai, M. Elhousni, and X. Huang, “An interactive LiDAR to camera calibration,” 2019 IEEE High Performance Extreme Computing Conference (HPEC), Waltham, USA, 2019.
[https://doi.org/10.1109/HPEC.2019.8916441]
-
F. Itami and T. Yamazaki, “A simple calibration procedure for a 2D LiDAR with respect to a camera,” IEEE Sensors Journal, vol. 19, no. 17, pp. 7553-7564, Sept., 2019.
[https://doi.org/10.1109/JSEN.2019.2915991]
-
J. Beltrán, C. Guindel, A. de la Escalera, and F. García, “Automatic extrinsic calibration method for LiDAR and camera sensor setups,” IEEE Transactions on Intelligent Transportation Systems, vol. 23, no. 10, pp. 17677-17689, Oct., 2022.
[https://doi.org/10.1109/TITS.2022.3155228]
-
G. Pandey, J. McBride, S. Savarese, and R. Eustice, “Automatic extrinsic calibration of vision and lidar by maximizing mutual information,” Journal of Field Robotics, vol. 32, no. 5, pp. 696-722, Aug., 2015.
[https://doi.org/10.1002/rob.21542]
-
P. Moghadam, M. Bosse, and R. Zlot, “Line-based extrinsic calibration of range and image sensors,” 2013 IEEE International Conference on Robotics and Automation (ICRA), Karlsruhe, Germany, pp. 3685-3691, 2013.
[https://doi.org/10.1109/ICRA.2013.6631095]
-
J. Jiang, P. Xue, S. Chen, Z. Liu, X. Zhang, and N. Zheng, “Line feature based extrinsic calibration of LiDAR and camera,” 2018 IEEE International Conference on Vehicular Electronics and Safety (ICVES), pp. 1-6, Madrid, Spain, 2018.
[https://doi.org/10.1109/ICVES.2018.8519493]
-
J. Jeong, Y. Cho, and A. Kim, “The Road is Enough! Extrinsic Calibration of Non-overlapping Stereo Camera and LiDAR using Road Information,” IEEE Robotics and Automation Letters, vol. 4, no. 3, pp. 2831-2838, Jul., 2019.
[https://doi.org/10.1109/LRA.2019.2921648]
-
A. I. Mourikis and S. I. Roumeliotis, “A multi-state constraint Kalman filter for vision-aided inertial navigation.” 2007 IEEE International Conference on Robotics and Automation (ICRA), Roma, Italy, pp. 3565-3572, 2007.
[https://doi.org/10.1109/ROBOT.2007.364024]
-
G. Pandey, J. McBride, S. Savarese, and R. Eustice, “Automatic targetless extrinsic calibration of a 3D lidar and camera by maximizing mutual information,” Twenty-Sixth AAAI Conference on Artificial Intelligence, vol. 26, no. 1, pp. 2053-2059, 2012.
[https://doi.org/10.1609/aaai.v26i1.8379]
-
R. Ishikawa, T. Oishi, and K. Ikeuchi, “LiDAR and Camera Calibration Using Motions Estimated by Sensor Fusion Odometry,” 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, pp. 7342-7349, 2018.
[https://doi.org/10.1109/IROS.2018.8593360]
- M. Ester, H.-P. Kriegel, J. Sander, and X. Xu, “A Density-Based Algorithm for Discovering Clusters in Large Spatial Databases with Noise,” KDD’96: Proceedings of the Second International Conference on Knowledge Discovery and Data Mining, Portland, USA, pp. 226-231, 1996, [Online], https://cdn.aaai.org/KDD/1996/KDD96-037.pdf?source=post_page, .
-
M. A. Fischler and R. C. Bolles, “Random sample consensus: A paradigm for model fitting with applications to image analysis and automated cartography,” Communications of the ACM, vol. 24, no. 6, pp. 381-395, Jun., 1981.
[https://doi.org/10.1145/358669.358692]
-
G. Yan, F. He, C. Shi, P. Wei, X. Cai, and Y. Li, “Joint camera intrinsic and LiDAR-camera extrinsic calibration,” 2023 IEEE International Conference on Robotics and Automation (ICRA), London, United Kingdom, pp. 11446-11452, 2023.
[https://doi.org/10.1109/ICRA48891.2023.10160542]
- Ceres Solver, [Online], http://ceres-solver.org/, , Accessed: Sept. 5, 2024.
2020~현재 서울대학교 공과대학 기계공학부 학사과정
관심분야: Robotics, 3D Vision
2019~현재 서울대학교 공과대학 기계항공공학부 학사과정
관심분야: Robotics, SLAM, Sensor Fusion
2022 서울대학교 공과대학 기계공학과(학사)
2023~현재 서울대학교 공과대학 기계공학과(석사)
관심분야: 3D Vision, Perception, Geometry
2005 서울대학교 기계항공공학과(공학사)
2007 서울대학교 기계항공공학전공(공학석사)
2012 미시간대학교 기계공학 전공(공학박사)
2014~2021 한국과학기술원 건설및환경공학과 부교수
2021~현재 서울대학교 공과대학 기계공학부 부교수
관심분야: 영상기반 SLAM

![[Fig. 2] [Fig. 2]](/xml/45116/JKROS_2025_v20n2_322_f002.jpg)
![[Fig. 3] [Fig. 3]](/xml/45116/JKROS_2025_v20n2_322_f003.jpg)
![[Fig. 4] [Fig. 4]](/xml/45116/JKROS_2025_v20n2_322_f004.jpg)