본 포스트는 공부용으로 작성되었습니다.
틀린 부분이나 수정해야 할 부분이 있다면 말씀해주시면 확인 후 반영하겠습니다.
본 포스트에서는 Visual SLAM의 성능 평가를 위하여 ground truth (GT) 데이터를 취득한 후 주로 수행하는 Hand-eye calibration에 대해 설명한다.
Introduction

Visual SLAM의 성능을 평가하기 위해서는 다양한 방법들이 존재하지만 실내에서는 주로 모션 캡쳐 시스템을 활용하여 ground truth (GT) 데이터를 취득한 후 성능을 평가한다. 모션 캡쳐 시스템은 일반적으로 카메라에 IR 반사 마커를 부착하여 GT 좌표계
그러나 이렇게 얻은 GT trajectory를 바로 성능 평가에 사용하게 되면 SLAM trajectory와 GT trajectory의 원점이 다르므로 서로 다른 궤적이 만들어지게 된다. 따라서 Umeyama 방법과 같이 두 trajectory를 최대한 정렬(alignment)한 후 성능을 평가하는데 이 때, 어떻게 두 trajectory가 겹쳐지느냐에 따라 결과가 달라지므로 상대적으로 부정확한 결과를 얻을 확률이 높아진다. 따라서 이러한 문제를 해결하기 위해 GT 좌표계

즉, hand-eye calibration (이하 HE)은 위 그림에서
Eye-in-hand calibration
HE는 로봇 베이스와 카메라 사이의 extrinsic을 구하는 방법(eye-to-hand)이 있고 로봇팔의 end effector와 팔 끝에 부착된 카메라 사이의 extinsic을 구하는 방법(eye-in-hand)이 있다. 본 포스트에서 설명할 GT 좌표계와 카메라 좌표계 사이의 extrinsic은 이 중 eye-in-hand를 사용하여 구할 수 있다.
본 포스팅에서는 GT 좌표계
Problem formulation

모션 캡쳐 방에 체커보드(또는 circle, apriltags 등)를 놓고 카메라가 체커보드를 바라보면서 GT trajectory 로깅을 시작한다. 카메라가 움직일 때마다 IR 반사 마커도 같이 움직이므로 위 그림과 같이 두 개의 trajectory가 생성된다.

두 trajectory에서 가장 앞의

위 식을 시각화하면 아래 그림과 같다.

즉,
-
-
-
위 공식은 순차적인
How to solve ?
Park-Martin method
Park-Martin 방법은 주어진 수식
위
따라서 순차적으로
Find
우선
이 때,
-
-
-
-
-
(
Lie theory에서 adjoint matrix of SO(3)의 성질로 인해 다음과 같은 유용한 관계들이 도출된다.
위 변환 관계는 많이 활용되기 때문에 알아놓으면 유용하다. Adjoint matrix에 대한 더 자세한 내용은 Lie Theory 개념 정리 포스트를 참조하면 된다.
Solve least squares for
현실 세계의 데이터는 노이즈가 반드시 포함되어 있으므로
-
-
일반적으로 위 식은 SE3군을 포함하므로 비선형 최소제곱법(non-linear least squares)을 통해 풀어야 한다. Park-martin 방법은 위 식을 이전에 유도한
위 식에서 회전행렬
-
위 식의 자세한 유도 과정에 대해 궁금한 독자들은 [7]을 참조하면 된다.
Find
Solve least squares for
위 식은
-
-
Code implementation
OpenCV에서 handeye calibration 관련 함수들을 보면 calibrateHandEyePark() 이라는 함수가 존재한다[3]. 해당 함수가 Park-Martin 방법을 사용하여 HE를 수행하는 코드이다.
//Reference:
//F. Park, B. Martin, "Robot Sensor Calibration: Solving AX = XB on the Euclidean Group."
//In IEEE Transactions on Robotics and Automation, 10(5): 717-721, 1994.
//Matlab code: http://math.loyola.edu/~mili/Calibration/
static void calibrateHandEyePark(const std::vector<Mat>& Hg, const std::vector<Mat>& Hc,
Mat& R_cam2gripper, Mat& t_cam2gripper)
{
Mat M = Mat::zeros(3, 3, CV_64FC1);
for (size_t i = 0; i < Hg.size(); i++)
{
for (size_t j = i+1; j < Hg.size(); j++)
{
Mat Hgij = homogeneousInverse(Hg[j]) * Hg[i];
Mat Hcij = Hc[j] * homogeneousInverse(Hc[i]);
Mat Rgij = Hgij(Rect(0, 0, 3, 3));
Mat Rcij = Hcij(Rect(0, 0, 3, 3));
Mat a, b;
Rodrigues(Rgij, a);
Rodrigues(Rcij, b);
M += b * a.t();
}
}
Mat eigenvalues, eigenvectors;
eigen(M.t()*M, eigenvalues, eigenvectors);
Mat v = Mat::zeros(3, 3, CV_64FC1);
for (int i = 0; i < 3; i++) {
v.at<double>(i,i) = 1.0 / sqrt(eigenvalues.at<double>(i,0));
}
Mat R = eigenvectors.t() * v * eigenvectors * M.t();
R_cam2gripper = R;
int K = static_cast<int>((Hg.size()*Hg.size() - Hg.size()) / 2.0);
Mat C(3*K, 3, CV_64FC1);
Mat d(3*K, 1, CV_64FC1);
Mat I3 = Mat::eye(3, 3, CV_64FC1);
int idx = 0;
for (size_t i = 0; i < Hg.size(); i++)
{
for (size_t j = i+1; j < Hg.size(); j++, idx++)
{
Mat Hgij = homogeneousInverse(Hg[j]) * Hg[i];
Mat Hcij = Hc[j] * homogeneousInverse(Hc[i]);
Mat Rgij = Hgij(Rect(0, 0, 3, 3));
Mat tgij = Hgij(Rect(3, 0, 1, 3));
Mat tcij = Hcij(Rect(3, 0, 1, 3));
Mat I_tgij = I3 - Rgij;
I_tgij.copyTo(C(Rect(0, 3*idx, 3, 3)));
Mat A_RB = tgij - R*tcij;
A_RB.copyTo(d(Rect(0, 3*idx, 1, 3)));
}
}
Mat t;
solve(C, d, t, DECOMP_SVD);
t_cam2gripper = t;
}
SLAM trajectory evaluation
필자가 생각하는 실내에서 Visual SLAM 성능을 평가하기 위한 과정은 다음과 같다.
- 모션 캡쳐 장비를 사용하여 GT trajectory 데이터를 획득하고 동시에 센서 데이터를 로깅한다.
- 체커보드(또는 circle, apriltags 등)을 놓고 HE를 위한 데이터 로깅을 수행한다.
- HE를 수행하여 GT 좌표계(hand)와 카메라 좌표계(eye) 간 extrinsic을 구한다.
- 센서 데이터를 사용하여 SLAM trajectory를 생성한다.
- SLAM trajectory와 GT trajectory의 시작 지점과 샘플링 주기가 서로 다르므로 이를 맞춰준다.
- SLAM trajectory에 extrinsic을 적용한 후 GT trajectory와 정렬하여 성능 평가를 수행한다.
이 때, 간과하기 쉬운 부분이 5번 과정이다. SLAM에서 로깅한 trajectory 정보와 GT trajectory 정보는 서로 다른 주기로 로깅되었기 때문에 시간 간격이 다르다. 또한 GT trajectory의 시작 지점과 SLAM trajectory의 시작 지점이 서로 다르기 때문에 이에 대한 고려없이 바로 trajectory evaluation을 수행한다면 정확한 성능 평가 결과를 얻을 수 없다. 따라서 이러한 문제를 해결하기 위해서 주기가 다른 두 신호를 정렬하는 방법을 사용해야 한다.

time alignment using cross-correlation
Cross-correlation을 사용하면 주기가 서로 다른 두 샘플링 신호의 시간 지연

Resampling

References
[1] Hand-Eye Calibration - TUM
[2] OpenCV - calibrateHandeye()
[3] github - OpenCV calibrateHandEyePark()
[4] R. Y. Tsai and R. K. Lenz, "A new technique for fully autonomous and efficient 3D robotics hand/eye calibration." In IEEE Transactions on Robotics and Automation, vol. 5, no. 3, pp. 345-358, June 1989.
[5] F. Park, B. Martin, "Robot Sensor Calibration: Solving AX = XB on the Euclidean Group." In IEEE Transactions on Robotics and Automation, 10(5): 717-721, 1994.
[6] K. Daniilidis, "Hand-Eye Calibration Using Dual Quaternions." In The International Journal of Robotics Research,18(3): 286-298, 1998.
[7] Nadas, A., 1978. Least squares and maximum likelihood estimates of rigid motion. IBM Res. Rep.
[8] Cross-correlation signal alignment - gist
'Fundamental' 카테고리의 다른 글
[Math] Useful Mathematical Identities and Tricks 정리 (2) | 2024.02.04 |
---|---|
확률 이론(Probability Theory) 개념 정리 Part 1 - Probability, Random Variable, Distribution (5) | 2023.11.13 |
3D 강체 변환(Rigid Body Transformation) 개념 정리 (6) | 2023.01.24 |
[SLAM] 에러와 자코비안 정리(Errors and Jacobians) 정리 Part 2 (3) | 2023.01.13 |
[SLAM] 에러와 자코비안 정리(Errors and Jacobians) 정리 Part 1 (17) | 2023.01.08 |