ICP Animation (Left Mouse : Drag, Right Mouse : Rotate, Wheel : Zoom)
Introduction
Iterative Closest Point (ICP) 알고리즘은 두 점군(pointcloud) 집합들이 주어졌을 때 각 점으로부터 최단 거리의 점들을 탐색하여 이를 바탕으로 반복적으로 정합(registration)하는 방법을 말한다. ICP는 주로 LiDAR SLAM에서 3D 스캔 데이터 정렬에 사용되며 Point-to-Point, Point-to-Plane 기법 등이 존재한다.
Example pointcloud data (2D)
2D Example (Left Mouse : Drag, Right Mouse : Rotate, Wheel : Zoom)

우선 2D 점군 데이터를 예시로 들어보자. 로봇이 2D 스캐너를 통해 다음과 같은 데이터를
sourcePoints = [ [-19, -15], [-18, -10], [-15, -9], [-14, -7], [-11, -6], [-9, -5], [-7, -6], [-4, -8], [-1, -11], [0, -14], [1, -17], [5, -20], [9, -24], [10, -25], [13, -24], [14, -25], [17, -25], [19, -22], [22, -18], [23, -16] ]
targetPoints = [ [-12, -8], [-12, -2], [-10, 1], [-10, 4], [-9, 6], [-6, 7], [-3, 8], [-1, 8], [3, 6], [6, 5], [10, 3], [14, 1], [17, 1], [19, 0], [22, 1], [24, 2], [27, 4], [26, 7], [27, 11], [27, 15] ]
Example pointcloud data (3D)
3D Example (Left Mouse : Drag, Right Mouse : Rotate, Wheel : Zoom)
하지만 실제 주어지는 데이터는 일반적으로 다음과 같은 3D 점군 데이터가 주어진다. 로봇이 3D 스캐너를 통해 다음과 같은 데이터를
sourcePoints = [ [-19, -15, 7], [-18, -10, 6], [-15, -9, 5], [-14, -7, 4], [-11, -6, 8], [-9, -5, 5], [-7, -6, 7], [-4, -8, 6], [-1, -11, 4], [0, -14, 6], [1, -17, 8], [5, -20, 7], [9, -24, 5], [10, -25, 6], [13, -24, 8], [14, -25, 5], [17, -25, 7], [19, -22, 6], [22, -18, 8], [23, -16, 7] ]
targetPoints = [ [-12, -8, 9], [-12, -2, 11], [-10, 1, 10], [-10, 4, 12], [-9, 6, 9], [-6, 7, 10], [-3, 8, 8], [-1, 8, 12], [3, 6, 11], [6, 5, 9], [10, 3, 8], [14, 1, 12], [17, 1, 11], [19, 0, 10], [22, 1, 8], [24, 2, 9], [27, 4, 11], [26, 7, 12], [27, 11, 9], [27, 15, 10] ]
Point-to-point ICP
With known data associations

ICP를 본격적으로 설명하기에 앞서 가장 쉬운 케이스를 먼저 생각해보자. 만약 위 그림과 같이 두 점군의 데이터들 간 관계(association, correspondence)
빨간색 점군을
- 위 식은 2D, 3D 데이터
위 식은 다음과 같은 최소제곱법 문제로 변환할 수 있다.
위 최소제곱법 문제는 비선형 항
Covariance SVD-based solution
결론부터 말하자면 두 점군에 대한 공분산 행렬
우선 이를 위해 두 점군의 무게 중심(centroid)를 먼저 구한다.

다음으로 기존의 모든 점들
위 결과를 사용하여 (
-
-
이 때, 두 점군의 이동 벡터
(
위 식을 전개하면 다음과 같다. 식이 전개되면서
따라서 최적화 수식은 다음과 같이 다시 쓸 수 있다. 마이너스 부호(
-
위 식의 세번째 줄을 보면
위 식의 네번째 줄을 보면
Covariance matrix of
두 데이터 집합과 이 주어졌을 때 두 데이터의 공분산 행렬은 다음과 같이 구할 수 있다.
1. 두 데이터의 평균을 구한다
2. 원본 데이터에서 각각 평균을 빼준다
3. 두 데이터의 공분산 행렬은 다음과 같이 구할 수 있다
따라서 최적의
공분산 행렬
Method 1 for
Lemma
임의의 postive definite 행렬과 정규직교행렬(orthonormal) 에 대하여 다음과 같은 Cauchy-Schwarz 부등식이 성립한다.
Proof
임의의 벡터에 대한 Cauchy-Schwarz 부등식은 다음과 같다.
-: 임의의 벡터
-: 벡터의 내적(inner product)
-: 벡터의 놈(norm) 은 다음과 같이 벡터 형태로 표현이 가능하다
위 식을 Cauchy-Schwarz 부등식에 대입하면 다음과 같은 식을 얻는다.
따라서 다음과 같은 Lemma를 얻는다.
만약
-
-
이를 다시 정리하면 다음과 같다.
위 식의 의미는
Method 2 for
(
Trace 성질에 의해 순서를 바꿔주게 되면 다음과 같다.
만약
-
따라서 앞서 method1에서 유도한 (
회전행렬의 최적해를 구할 때
With unknown data associations
이전 섹션에서 살펴본 최적해

위와 같이 대응 관계를 모르는 경우, 바로 구할 수 있는 closed form 해는 존재하지 않는다. 따라서 하나의 점으로부터 가장 가까운 점(closest point)을 대응점 쌍으로 설정하여 반복적(iterative)으로 최적해를 구하는 알고리즘이 Iterative Closest Point(ICP)이다. ICP의 전체적인 과정은 다음과 같다. (
- source 점군과 target 점군의 평균(또는 centroid)
를 구한다. - 각 점군에 두 평균을 빼줌으로써 평균을 0으로 정규화한다. (
) - 각 source 점들마다 최단 거리의 target 점들을 correspondence로 설정한다. (nearest neighborhood 알고리즘 사용 e.g., KD-tree)
- 공분산 행렬을 SVD 분해하여 회전행렬
을 구하고 평균 간 차이를 통해 이동 벡터 를 구한다. ( ) - source 점군을 최적해만큼 이동시킨다.
- 두 점군의 거리가 충분히 가까워질 때까지 1~5 과정을 반복한다.
ICP 과정을 그림으로 나타내면 다음과 같다.


지금까지 설명한 알고리즘을 가장 기본적인 ICP 알고리즘이라는 뜻에서 일반적으로 Vanila ICP라고 부른다. Vanila ICP는 구현하기 비교적 쉽고 초기 추정값(initial guess)가 정확하면 잘 동작한다는 장점이 있으나 일반적으로 수렴하는데 많은 반복 횟수가 필요하며 잘못된 correspondence에 영향을 많이 받아 결과가 안 좋아질 수 있는 한계점이 존재한다.
이러한 Vanila ICP의 한계점을 극복하기 위해 모든 점들이 아닌 점군의 부분 집합(e.g., 특징점)만 추출하여 ICP를 수행한다거나 point-to-plane과 같이 다른 대응 관계를 이용한다거나 correspondence에 가중치를 두어 outlier의 영향력을 축소한다거나 잠재적인 point outlier를 아예 제거하여 보다 강건한 ICP를 수행하는 등 많은 변형 ICP 방법들이 존재한다. 자세한 내용은 Cyrill 교수님의 ICP 강의 를 참고하면 된다.
Least squares point-to-point ICP (2D)
지금까지 설명했던 ICP 방법의 핵심은 두 점군의 공분산 행렬을 구한 후 SVD 분해하여 회전 행렬을
Least squares ICP는 대부분 과정이 기존 ICP와 동일하지만 매 iteration마다 최적해
SVD 해는 점군들의 correspondence가 point-to-point 대응점 쌍임을 가정하고 해를 구하지만 실제 ICP는 point-to-point 이외에도 다양한 에러 함수를 설정할 수 있으므로 Least squares ICP를 사용하면 이러한 에러함수를 일관되게 최적화할 수 있다. 또한 Robust estimator 같은 항을 사용하여 보다 outlier에 강건한 최적화를 수행할 수 있다.
Least squares ICP를 수행하기 위해 2차원 포즈 상태 변수
-
최적화 식은 기존의 (
- 에러 함수가 '예측값-관측값' 형태로 변경되어도 제곱이 되므로 전체 최적화 과정에는 영향을 주지 않는다. 다만 에러 함수에 모양에 따라 자코비안의 부호가 달라지므로 실제 코드 구현 시 이에 유의한다.
위 식은 비선형 최소제곱법의 형태를 띄므로 Gauss-Newton(GN) 또는 Levenberg-Marquardt(LM) 방법으로 풀 수 있다. GN 방법을 예로 들어 설명해보자. 미소한 변화량
위 식에서
-
모든 점들에 대한 에러 함수를 합치면 다음과 같이 점군에 대한 에러 함수가 된다.
점군에 대한 자코비안
GN 방법의 해는 다음과 같이 구할 수 있다. 유도 과정에 대해 궁금한 독자들은 에러와 자코비안 정리 포스팅을 참고하면 된다.
미소 증분량의 최적해
지금까지 설명한 과정을 source 점군이 더 이상 업데이트 되지 않을 때까지 반복한다. 이러한 과정을 Least squares ICP (2D ver.) 알고리즘이라고 부른다.
Gauss-Newton method (point-to-point ICP 2D)
- Nearest neighborhood (e.g., KD-tree) 방법을 통해 source 점에 가장 가까운 target 점들을 correspondence로 설정한다.
- (
)과 같이 에러함수를 정의한다. - 테일러 전개로 근사 선형화하여 자코비안을 구한다.
- 1차 미분 후 0으로 설정한다.
- 이 때 값을 구하고 이를 에러함수에 대입한다.
- 값이 수렴할 때 까지 반복한다.
Least squares point-to-point ICP (3D)
3D 점군에 대한 Least squares ICP는 2D 점군과 비교해서 자코비안을 제외하고 모든 과정이 동일하다. 이 때, 자코비안에 3차원 회전 행렬
Least squares ICP를 수행하기 위해 3차원 포즈 상태 변수
위 식은 비선형 최소제곱법의 형태를 띄므로 Gauss-Newton(GN) 또는 Levenberg-Marquardt(LM) 방법으로 풀 수 있다. GN 방법을 예로 들어 설명해보자. 미소한 변화량
- Lie theory-based optimization에 대한 내용은 에러와 자코비안 정리 포스팅을 참고하면 된다.
-
-
모든 점들에 대한 에러 함수를 합치면 다음과 같이 점군에 대한 에러 함수가 된다.
점군에 대한 자코비안
GN 방법의 해는 다음과 같이 구할 수 있다. 유도 과정에 대해 궁금한 독자들은 에러와 자코비안 정리 포스팅을 참고하면 된다.
미소 증분량의 최적해
지금까지 설명한 과정을 source 점군이 더 이상 업데이트 되지 않을 때까지 반복한다. 이러한 과정을 Least squares ICP (3D ver.) 알고리즘이라고 부른다.
Gauss-Newton method (point-to-point ICP 3D)
- Nearest neighborhood (e.g., KD-tree) 방법을 통해 source 점에 가장 가까운 target 점들을 correspondence로 설정한다.
- (
)과 같이 에러함수를 정의한다. - 테일러 전개로 근사 선형화하여 자코비안을 구한다.
- 1차 미분 후 0으로 설정한다.
- 이 때 값을 구하고 이를 에러함수에 대입한다.
- 값이 수렴할 때 까지 반복한다.
Point-to-plane ICP

기존 point-to-point ICP는 source 점과 target 점 사이의 유클리디언 거리(euclidean distance)를 최소화하는 방향으로 최적화를 수행하였다. 반면에 point-to-plane ICP는 source 점과 target 법선 벡터(normal vector) 거리를 최소화하는 방향으로 최적화를 수행한다. Point-to-plane의 원조격이 되는 논문은 [5][6][7]가 있다.
Point-to-plane 알고리즘은 point-to-point 대비 일반적으로 수렴 속도가 빠르며 노이즈와 outlier에 덜 민감하다는 특징이 있다. 반면에 법선 벡터를 계산한 후 최적화하는 과정이 추가되어 연산량이 증가한다는 trade-off 관계가 존재한다. 또한 point-to-point와 최적화 수식이 달라지므로 SVD 해를 구할 수 없고 least squares(=GN)을 통해서만 최적해를 구할 수 있다.
Least squares point-to-plane ICP (2D)
Point-to-plane ICP의 대부분의 과정은 point-to-point ICP와 동일하며 법선 벡터(normal vector)를 구하는 과정과 최적화 수식이 약간 변경되었다는 점이 다르다. Least squares ICP를 수행하기 위해 2차원 포즈 상태 변수
-
-
-
기존 point-to-point의 최적화 수식에 법선 벡터
2D의 경우 법선 벡터는 점
위 식은 비선형 최소제곱법의 형태를 띄므로 Gauss-Newton(GN) 또는 Levenberg-Marquardt(LM) 방법으로 풀 수 있다. GN 방법을 예로 들어 설명해보자. 미소한 변화량
위 식에서
-
-
모든 점들에 대한 에러 함수를 합치면 다음과 같이 점군에 대한 에러 함수가 된다.
점군에 대한 자코비안
GN 방법의 해는 다음과 같이 구할 수 있다. 유도 과정에 대해 궁금한 독자들은 에러와 자코비안 정리 포스팅을 참고하면 된다.
미소 증분량의 최적해
지금까지 설명한 과정을 source 점군이 더 이상 업데이트 되지 않을 때까지 반복한다. 이러한 과정을 Least squares ICP (2D ver.) 알고리즘이라고 부른다.
Gauss-Newton method (point-to-plane ICP 2D)
- Nearest neighborhood (e.g., KD-tree) 방법을 통해 source 점에 가장 가까운 target 점들을 correspondence로 설정한다.
- target 점들의 법선 벡터(normal vector)
을 계산한다. (2D: ) - (
)과 같이 에러함수를 정의한다. - 테일러 전개로 근사 선형화하여 자코비안을 구한다.
- 1차 미분 후 0으로 설정한다.
- 이 때 값을 구하고 이를 에러함수에 대입한다.
- 값이 수렴할 때 까지 반복한다.
Least squares point-to-plane ICP (3D)
3D 역시 point-to-plane ICP의 대부분의 과정은 point-to-point ICP와 동일하며 법선 벡터(normal vector)를 구하는 과정과 최적화 수식이 약간 변경되었다는 점이 다르다. Least squares ICP를 수행하기 위해 3차원 포즈 상태 변수
-
-
기존 point-to-point의 최적화 수식에 법선 벡터
법선 벡터는 다양한 방법을 통해 구할 수 있는데 3D의 경우 점
위 식은 비선형 최소제곱법의 형태를 띄므로 Gauss-Newton(GN) 또는 Levenberg-Marquardt(LM) 방법으로 풀 수 있다. GN 방법을 예로 들어 설명해보자. 미소한 변화량
- Lie theory-based optimization에 대한 내용은 에러와 자코비안 정리 포스팅을 참고하면 된다.
-
-
모든 점들에 대한 에러 함수를 합치면 다음과 같이 점군에 대한 에러 함수가 된다.
점군에 대한 자코비안
GN 방법의 해는 다음과 같이 구할 수 있다. 유도 과정에 대해 궁금한 독자들은 에러와 자코비안 정리 포스팅을 참고하면 된다.
미소 증분량의 최적해
지금까지 설명한 과정을 source 점군이 더 이상 업데이트 되지 않을 때까지 반복한다. 이러한 과정을 Least squares ICP (3D ver.) 알고리즘이라고 부른다.
Gauss-Newton method (point-to-plane ICP 3D)
- Nearest neighborhood (e.g., KD-tree) 방법을 통해 source 점에 가장 가까운 target 점들을 correspondence로 설정한다.
- target 점들의 법선 벡터(normal vector)
을 계산한다. - (
)과 같이 에러함수를 정의한다. - 테일러 전개로 근사 선형화하여 자코비안을 구한다.
- 1차 미분 후 0으로 설정한다.
- 이 때 값을 구하고 이를 에러함수에 대입한다.
- 값이 수렴할 때 까지 반복한다.
Generalized-ICP (GICP)
Generalized-ICP(GICP)는 기존 ICP 알고리즘들과 달리 점을 확률 기반으로 모델링하여 점군 간 변환을 추정하는 알고리즘이다. GICP는 공분산 행렬의 형태에 따라 point-to-point, point-to-plane, plane-to-plane ICP 방법을 모두 포함할 수 있다. 이러한 이유로 인해 일반화된(generalized) ICP라는 이름이 붙여진 것으로 보인다. 하지만 가장 가까운 대응점 쌍(correspondence)를 구할 때는 여전히 확률 기반이 아닌 거리 기반(nearest neighbor, KD-tree)을 사용하여 KNN 알고리즘의 속도는 유지하였다.
GICP[8]는 대응점 쌍이 구해졌다고 가정한 상태에서 수식을 유도한다. Source 점군이
만약 두 점군이 노이즈 또는 outlier 없이 정확히 유클리디언 거리만큼 떨어져 있는 경우 두 점 사이에는 다음과 같은 변환 관계가 성립한다.
두 점 사이의 임의의 변환
와 같이 거리 함수
- 두 점
Linear transformation of gaussian random variable
확률 변수가 와 같이 평균이 이고 공분산이 인 가우시안 분포를 따른다고 했을 때, 임의의 행렬 에 대하여 를 만족하는 또한 확률 변수이고 인 가우시안 분포를 따른다.
보다 자세한 내용은 확률 이론 포스팅을 참조하면 된다.
위 식은
따라서 (
Point-to-point ICP in GICP
GICP가 일반화된(generalized) ICP로 불리는 이유는 (
만약 공분산 행렬이 다음과 같은 경우 point-to-point ICP 수식이 유도된다.
위 식을 (
이는 point-to-point ICP의 수식과 정확히 일치한다.
Point-to-plane ICP in GICP

앞서 설명한 point-to-plane ICP는 source 점과 target 평면 사이의 거리를 최소화하는 알고리즘이었다. 따라서 target 평면의 법선 벡터
위 식에서
이에 따라 (
이는 GICP 수식 (
엄밀하게 말하면 투영 행렬
Projection Matrix
투영 행렬가 rank deficient인 이유는 고차원 벡터 공간의 점(또는 벡터)를 저차원 부분 공간으로 투영(projection)하는 역할을 하기 때문이다. Point-to-plane 예시에서는 source 점 가 target 점 가 이루는 평면의 부분 공간으로 투영(projection)되는 것으로 해석할 수 있다. 투영 행렬에 대한 자세한 설명은 선형대수학 개념 정리 포스팅을 참조하면 된다.
Plane-to-plane ICP in GICP
마지막으로 GICP는 source 평면과 target 평면 사이의 거리를 최소화하는 plane-to-plane ICP 또한 수행할 수 있다. 이는 단순히 (
이에 따라 여러 가정을 통해 plane에 대한 공분산 행렬을 모델링한다.
- 스캔 데이터는 실제 3차원 공간의 부드러운 다양체(2-manifold)를 샘플링 한 것이므로 모든 포인트에서 미분 가능하다(=법선 벡터를 구할 수 있다).
- 서로 다른 시점(t,t+1)에서 샘플링한 데이터는 일반적으러 정확히 같은 점을 샘플링하지 않는다. 따라서 가장 가까운 대응점 쌍(nearest correspondence)는 0이 될 수 없다.
- 샘플링된 점은 평면의 수평한 방향으로 높은 공분산을 가지고 수직한(법선벡터) 방향으로는 낮은 공분산을 가진다고 간주한다.
만약
-

-
-
위 식을 (
법선 벡터를 추정하는 방법은 다양하게 있으며 GICP 논문에서는 각 스캔한 점에 대해 가장 가까운 주변의 20개의 점을 KD-Tree를 통해 구한 후 공분산 행렬에 PCA를 사용하여 법선 벡터를 계산하였다. 이 때, 가장 작은 고유값(eigenvalue)에 해당하는 고유 벡터(eigenvector)가 법선 벡터에 해당한다.
Least squares GICP (3D)
GICP는 (
-
-
-
-
기존 ICP들과 달리 GICP는 확률 기반으로 모델링하기였기 때문에 mahalanobis norm
Gauss-Newton 수식 유도는 least-squares point-to-point ICP와 완전히 동일하다.
- Lie theory-based optimization에 대한 내용은 에러와 자코비안 정리 포스팅을 참고하면 된다.
모든 점들에 대한 에러 함수를 합치면 다음과 같이 점군에 대한 에러 함수가 된다.
위 식을 자세하게 전개하면 (
점군에 대한 자코비안
GN 방법의 해는 다음과 같이 구할 수 있다. 유도 과정에 대해 궁금한 독자들은 에러와 자코비안 정리 포스팅을 참고하면 된다.
미소 증분량의 최적해
지금까지 설명한 과정을 source 점군이 더 이상 업데이트 되지 않을 때까지 반복한다. 이러한 과정을 Least squares GICP (3D ver.) 알고리즘이라고 부른다.
Gauss-Newton method (GICP 3D)
- Nearest neighborhood (e.g., KD-tree) 방법을 통해 source 점에 가장 가까운 target 점들을 correspondence로 설정한다.
- 공분산
의 초기값을 설정한다. (fast_gicp[9]에서는 plane-to-plane 공분산이 기본값으로 설정되어 있음) - (
)과 같이 에러함수를 정의한다. - 테일러 전개로 근사 선형화하여 자코비안을 구한다.
- 1차 미분 후 0으로 설정한다.
- 이 때 값을 구하고 이를 에러함수에 대입한다.
- 값이 수렴할 때 까지 반복한다.
References
[2] (blog) ICP (Iterative Closest Point) 와 Point Cloud Registration - Jinsol Kim님 블로그
[3] (blog) Slam 3-2강 (ICP algorithm & Unknown Data Association) 요약 - taeyoung96님 블로그
[4] (youtube) [AIX7063] Inclass 19 | Iterative Closest Point 강의
[9] (code) SMRT-AIST/fast_gicp
p.s.) ICP의 과정에 대해 코드와 함께 상세하게 정리된 Jupyter notebook 링크를 공유한다. 애니메이션과 함께 매우 잘 정리되어있어 직관적으로 이해하기 쉬우니 참고하면 좋을 것 같다.