9.45 동차 변환 행렬의 역변환 계산

1. 역변환의 필요성

동차 변환 행렬 \mathbf{T}가 좌표계 \{A\}에서 \{B\}로의 변환을 나타낸다면, 그 역 \mathbf{T}^{-1}\{B\}에서 \{A\}로의 변환을 나타낸다. 로봇 공학에서 다음과 같은 상황에서 역변환이 빈번히 필요하다.

  • 좌표계 변환의 방향 전환
  • 매니퓰레이터 역기구학 해석
  • 카메라 외부 매개변수의 역변환
  • SLAM 그래프 최적화의 잔차 계산
  • 손-눈 캘리브레이션 방정식

일반적인 4 \times 4 행렬 역행렬 계산은 O(n^3)의 비용을 요구하지만, 동차 변환 행렬은 그 특수한 구조 덕분에 훨씬 효율적인 닫힌 형태로 역을 계산할 수 있다.

2. 역변환의 닫힌 형태

동차 변환 행렬 \mathbf{T} = \begin{bmatrix}\mathbf{R} & \mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix}의 역은 다음과 같다.

\mathbf{T}^{-1} = \begin{bmatrix}\mathbf{R}^T & -\mathbf{R}^T\mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix}

이 공식의 두 부분을 살펴본다.

  • 회전 부분의 역: \mathbf{R}^{-1} = \mathbf{R}^T (회전 행렬의 직교성)
  • 병진 부분의 역: -\mathbf{R}^T\mathbf{t} (단순한 부호 반전이 아님)

3. 유도

3.1 행렬 곱으로 검증

\mathbf{T}\mathbf{T}^{-1} = \mathbf{I}임을 블록 단위로 확인한다.

\mathbf{T}\mathbf{T}^{-1} = \begin{bmatrix}\mathbf{R} & \mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix}\begin{bmatrix}\mathbf{R}^T & -\mathbf{R}^T\mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix}

좌상단 블록: \mathbf{R}\mathbf{R}^T = \mathbf{I}_3.

우상단 블록: \mathbf{R}(-\mathbf{R}^T\mathbf{t}) + \mathbf{t} = -\mathbf{R}\mathbf{R}^T\mathbf{t} + \mathbf{t} = -\mathbf{t} + \mathbf{t} = \mathbf{0}.

좌하단 블록: \mathbf{0}^T\mathbf{R}^T + 1 \cdot \mathbf{0}^T = \mathbf{0}^T.

우하단 블록: \mathbf{0}^T(-\mathbf{R}^T\mathbf{t}) + 1 \cdot 1 = 1.

따라서

\mathbf{T}\mathbf{T}^{-1} = \begin{bmatrix}\mathbf{I}_3 & \mathbf{0} \\ \mathbf{0}^T & 1\end{bmatrix} = \mathbf{I}_4

이며 공식이 검증된다.

3.2 합성 형태로의 유도

\mathbf{T} = \mathbf{T}_{\text{trans}}(\mathbf{t}) \cdot \mathbf{T}_{\text{rot}}(\mathbf{R})의 분해를 이용하면

\mathbf{T}^{-1} = \mathbf{T}_{\text{rot}}(\mathbf{R})^{-1} \cdot \mathbf{T}_{\text{trans}}(\mathbf{t})^{-1} = \mathbf{T}_{\text{rot}}(\mathbf{R}^T) \cdot \mathbf{T}_{\text{trans}}(-\mathbf{t})

이 된다. 두 분해된 변환을 다시 합성하면

\begin{bmatrix}\mathbf{R}^T & \mathbf{0} \\ \mathbf{0}^T & 1\end{bmatrix}\begin{bmatrix}\mathbf{I}_3 & -\mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix} = \begin{bmatrix}\mathbf{R}^T & -\mathbf{R}^T\mathbf{t} \\ \mathbf{0}^T & 1\end{bmatrix}

이며, 닫힌 형태와 일치한다.

4. 병진 부분의 기하학적 해석

역변환의 병진 부분이 단순히 -\mathbf{t}가 아닌 -\mathbf{R}^T\mathbf{t}인 이유를 기하학적으로 이해하자. 원래 변환 \mathbf{T}가 좌표계 \{A\}의 점을 좌표계 \{B\}의 좌표로 표현하는 경우, \mathbf{t}\{A\}의 원점이 \{B\}에서 어디에 위치하는지를 나타낸다. 역변환에서는 \{B\}의 원점이 \{A\}에서 어디에 있는지를 알아야 한다. 두 원점은 단순히 부호 반전된 위치 관계가 아니라, 회전 후의 좌표계에서 표현되므로 \mathbf{R}^T가 함께 작용한다.

또 다른 해석으로, \mathbf{T}가 좌표 변환이 아니라 강체의 운동을 나타낸다고 생각하면 다음과 같다. 강체가 회전 \mathbf{R} 후 병진 \mathbf{t}를 수행한 결과의 역은 “병진의 역 후 회전의 역“이며, 이를 행렬로 표현할 때 회전과 병진의 결합 순서를 고려하여 -\mathbf{R}^T\mathbf{t}가 도출된다.

5. 계산 비용

5.1 일반 역행렬 vs. 닫힌 형태

일반 4 \times 4 역행렬을 가우스 소거법으로 계산하면 약 64회의 곱셈과 분할 연산이 필요하다. 반면 동차 변환 행렬의 닫힌 형태 역은 다음의 연산만을 요구한다.

  • 회전 행렬의 전치: 비용 0 (인덱스 재배치만 필요)
  • -\mathbf{R}^T\mathbf{t} 계산: 9회 곱셈과 6회 덧셈

총 약 9회 곱셈과 9회 덧셈으로 충분하며, 일반 역행렬의 1/7 이하의 비용이다. 또한 가우스 소거의 수치적 오차도 발생하지 않는다.

5.2 메모리 효율성

역변환 결과를 새 행렬에 저장하지 않고 원본을 직접 변환하는 인플레이스(in-place) 구현도 가능하다. 회전 부분은 전치 연산으로, 병진 부분은 새 값으로 덮어쓰면 추가 메모리가 필요 없다.

6. 수치적 특성

6.1 수치 안정성

회전 행렬의 직교성이 정확히 유지되는 한, 역변환은 정확히 원본의 역이 된다. 부동 소수점 누적 오차로 회전 행렬이 정규 직교성에서 벗어나면, \mathbf{T}\mathbf{T}^{-1}이 단위 행렬에서 약간 벗어날 수 있다. 이런 경우 회전 부분의 재정규화가 필요하다.

6.2 이중 역의 등가성

(\mathbf{T}^{-1})^{-1} = \mathbf{T}가 정확히 성립한다.

((\mathbf{R}^T)^T) = \mathbf{R}, \quad -(\mathbf{R}^T)^T(-\mathbf{R}^T\mathbf{t}) = \mathbf{R}\mathbf{R}^T\mathbf{t} = \mathbf{t}

이 항등식은 검증용 단위 테스트에 사용된다.

7. 합성과 역의 관계

여러 변환의 합성에 대한 역은 각 변환의 역을 역순으로 곱한 것과 같다.

(\mathbf{T}_n\mathbf{T}_{n-1}\cdots\mathbf{T}_1)^{-1} = \mathbf{T}_1^{-1}\mathbf{T}_2^{-1}\cdots\mathbf{T}_n^{-1}

이 일반 군 성질이 동차 변환 행렬에도 적용된다.

8. 좌표계 변환에서의 활용

8.1 첨자 반전

\mathbf{T}_{A,B}가 좌표계 \{A\}에서 \{B\}로의 변환이라면

\mathbf{T}_{A,B}^{-1} = \mathbf{T}_{B,A}

이다. 즉, 역변환은 첨자를 뒤집은 변환과 같다. 이 관계가 좌표계 변환의 방향을 자유롭게 전환하는 기본 도구이다.

8.2 카메라 외부 매개변수

카메라의 외부 매개변수는 일반적으로 월드 좌표계에서 카메라 좌표계로의 변환 \mathbf{T}_{W,C}로 주어진다. 카메라 위치를 월드 좌표계에서 표현하려면 역변환이 필요하다.

\mathbf{T}_{C,W} = \mathbf{T}_{W,C}^{-1}

카메라의 위치는 \mathbf{T}_{C,W}의 우상단 블록이다.

9. 매니퓰레이터 역기구학에의 활용

매니퓰레이터의 순기구학 {}^0\mathbf{T}_n(\boldsymbol{\theta})로부터 목표 자세 \mathbf{T}_d를 달성하는 관절 각도 \boldsymbol{\theta}를 구하는 역기구학에서 역변환이 사용된다. 예를 들어 손목 분리 기법(wrist decoupling)에서는 손목 위치를 분리한 후

{}^0\mathbf{T}_3 = ({}^3\mathbf{T}_n)^{-1} \cdot {}^0\mathbf{T}_n

와 같은 변환을 통해 손목 자세를 분리적으로 처리한다.

10. SLAM과 포즈 그래프에서의 활용

포즈 그래프 SLAM에서 두 노드 \mathbf{T}_i\mathbf{T}_j 사이의 측정된 상대 변환 \Delta\mathbf{T}_{ij}^{\text{측정}}과 예측된 상대 변환 \Delta\mathbf{T}_{ij}^{\text{예측}} = \mathbf{T}_i^{-1}\mathbf{T}_j의 차이를 잔차로 계산한다. 잔차 회전과 병진이 최적화의 입력이 된다.

\mathbf{r}_{ij} = \log(\Delta\mathbf{T}_{ij}^{\text{측정}-1} \cdot \Delta\mathbf{T}_{ij}^{\text{예측}})

여기서 \logSE(3)의 로그 사상이다. 역변환이 잔차 계산의 핵심 연산이다.

11. 손-눈 캘리브레이션의 활용

손-눈 캘리브레이션의 표준 방정식 \mathbf{A}\mathbf{X} = \mathbf{X}\mathbf{B}에서 \mathbf{A}\mathbf{B}는 두 자세 사이의 상대 변환이며, 각각 매니퓰레이터의 두 자세와 카메라의 두 자세로부터 계산된다. 이 상대 변환의 계산이 역변환과 행렬 곱의 결합이다.

\mathbf{A} = \mathbf{T}_1^{-1}\mathbf{T}_2 = \begin{bmatrix}\mathbf{R}_1^T\mathbf{R}_2 & \mathbf{R}_1^T(\mathbf{t}_2 - \mathbf{t}_1) \\ \mathbf{0}^T & 1\end{bmatrix}

12. 일반적 코드 구현 패턴

동차 변환 행렬의 역변환은 간단한 코드로 구현될 수 있다.

function inverse(T):
    R = T[0:3, 0:3]      # 회전 부분 추출
    t = T[0:3, 3]        # 병진 부분 추출
    R_inv = transpose(R) # 전치
    t_inv = -R_inv * t   # 새 병진
    T_inv = [[R_inv, t_inv], [0, 0, 0, 1]]
    return T_inv

이 알고리즘은 어떤 행렬 라이브러리에서도 효율적으로 구현될 수 있으며, 일반 역행렬 함수보다 훨씬 빠르고 안정적이다.

13. 참고 문헌

  • Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
  • Craig, J. J. (2018). Introduction to Robotics: Mechanics and Control (4th ed.). Pearson.
  • Spong, M. W., Hutchinson, S., & Vidyasagar, M. (2020). Robot Modeling and Control (2nd ed.). Wiley.
  • Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
  • Lynch, K. M., & Park, F. C. (2017). Modern Robotics: Mechanics, Planning, and Control. Cambridge University Press.

version: 1.0