11.11 수반 표현(Adjoint Representation)
1. 수반 표현의 개요
수반 표현(adjoint representation)은 리 군이 자신의 리 대수에 작용하는 방식을 기술하는 표현이다. 이는 리 군 이론의 가장 중요한 개념 중 하나이며, 좌표계 변환, 자세 추정, 매니퓰레이터 운동학, 비선형 최적화 등 로봇공학의 다양한 영역에서 핵심적인 역할을 한다. 수반 표현은 두 가지 형태로 정의된다. 리 군 수준의 수반 표현 \mathrm{Ad}와 리 대수 수준의 수반 표현 \mathrm{ad}이다. 이 두 사상은 지수 사상으로 연결되며, 리 군과 리 대수의 구조를 이해하는 데 필수적이다.
2. 표현의 일반적 개념
2.1 군 표현
군 G의 표현은 G를 어떤 선형 공간 V 위의 가역 선형 변환의 군으로 사상하는 군 준동형사상이다.
\rho : G \to GL(V)
표현은 군의 구조를 선형 변환의 언어로 번역하며, 추상적인 군을 구체적으로 다룰 수 있게 한다.
2.2 충실 표현
표현이 일대일이면 충실(faithful) 표현이라 한다. 충실 표현은 군의 모든 정보를 보존한다.
2.3 자명 표현
모든 군 원소를 항등 변환으로 사상하는 표현을 자명 표현이라 한다. 이는 가장 단순한 표현이지만 정보를 보존하지 않는다.
3. 군의 자기 작용
3.1 내부 자기동형사상
리 군 G의 원소 g에 대해 다음의 사상을 정의한다.
\Psi_g : G \to G, \quad \Psi_g(h) = ghg^{-1}
이 사상은 군의 내부 자기동형사상(inner automorphism)이며, 군 구조를 보존한다.
3.2 켤레
위의 사상에서 ghg^{-1}를 h의 켤레(conjugate)라 한다. 켤레 연산은 군의 구조를 분석하는 중요한 도구이다.
4. 군 수준의 수반 표현
4.1 정의
\Psi_g는 리 군의 자기 동형사상이며, 항등원을 항등원으로 사상한다. 따라서 항등원에서의 미분이 자연스럽게 정의되며, 이것이 리 대수 위의 선형 사상이다.
\mathrm{Ad}_g : \mathfrak{g} \to \mathfrak{g}, \quad \mathrm{Ad}_g(X) = (d\Psi_g)_e(X)
행렬 리 군에서는 다음의 단순한 형태이다.
\mathrm{Ad}_g(X) = gXg^{-1}
이 사상은 군 원소 g가 리 대수 원소 X에 작용하는 방식을 기술한다.
4.2 표현으로서의 \mathrm{Ad}
\mathrm{Ad} : G \to GL(\mathfrak{g})는 다음을 만족하는 군 표현이다.
\mathrm{Ad}_{g_1g_2} = \mathrm{Ad}_{g_1}\mathrm{Ad}_{g_2}
\mathrm{Ad}_e = \mathrm{id}
따라서 \mathrm{Ad}는 리 군의 리 대수 위의 표현이며, 이를 수반 표현이라 한다.
4.3 의미
\mathrm{Ad}_g는 좌표계 변환을 의미한다. 한 좌표계에서의 무한소 운동(리 대수 원소)이 다른 좌표계에서 어떻게 표현되는지를 결정한다.
5. 리 대수 수준의 수반 표현
5.1 정의
수반 표현 \mathrm{Ad}의 항등원에서의 미분이 리 대수 위의 사상을 정의한다.
\mathrm{ad} : \mathfrak{g} \to \mathfrak{gl}(\mathfrak{g}), \quad \mathrm{ad}_X = (d\mathrm{Ad})_e(X)
이 사상의 명시적 형태는 리 괄호이다.
\mathrm{ad}_X(Y) = [X, Y]
따라서 \mathrm{ad}_X는 Y를 [X, Y]로 사상하는 선형 사상이다.
5.2 리 괄호로서의 \mathrm{ad}
리 대수 수준의 수반 표현은 리 괄호 그 자체이다. 이는 \mathrm{ad}가 리 대수의 가장 자연스러운 자기 작용임을 보여준다.
5.3 야코비 항등식과의 관계
\mathrm{ad}는 야코비 항등식을 다음과 같이 표현한다.
\mathrm{ad}_{[X, Y]} = [\mathrm{ad}_X, \mathrm{ad}_Y]
이는 \mathrm{ad}가 리 대수의 표현임을 보여준다.
6. 군과 대수 사이의 관계
6.1 지수 사상을 통한 연결
군 수준의 \mathrm{Ad}와 대수 수준의 \mathrm{ad}는 지수 사상으로 연결된다.
\mathrm{Ad}_{\exp(X)} = \exp(\mathrm{ad}_X)
여기서 우변의 \exp는 \mathrm{ad}_X : \mathfrak{g} \to \mathfrak{g}의 지수이며, 선형 사상의 지수이다.
6.2 명시적 표현
이 관계를 행렬로 표현하면
\mathrm{Ad}_{e^X} = e^{\mathrm{ad}_X} = \sum_{k=0}^{\infty}\frac{(\mathrm{ad}_X)^k}{k!}
여기서 (\mathrm{ad}_X)^k는 \mathrm{ad}_X의 k번 합성이다.
7. SO(3)의 수반 표현
7.1 행렬 형태
SO(3)의 원소 \mathbf{R}의 수반 표현은 다음과 같다.
\mathrm{Ad}_{\mathbf{R}}(\boldsymbol{\omega}) = \mathbf{R}\boldsymbol{\omega}
이는 회전 행렬에 의한 벡터 변환이며, 좌표계 변환에서 익숙한 식이다.
7.2 차원 표현 vs 3차원 표현
SO(3)에서 리 대수 \mathfrak{so}(3)은 3차원이며, 따라서 \mathrm{Ad}_{\mathbf{R}}은 3 \times 3 행렬로 표현된다. 이 행렬이 정확히 \mathbf{R}이다.
7.3 \mathrm{ad} 사상
\mathrm{ad}_{\boldsymbol{\omega}}는 \mathfrak{so}(3) \to \mathfrak{so}(3)의 사상이며, 다음과 같이 표현된다.
\mathrm{ad}_{\boldsymbol{\omega}_1}(\boldsymbol{\omega}_2) = [\boldsymbol{\omega}_1, \boldsymbol{\omega}_2]_{\mathfrak{so}(3)} = \boldsymbol{\omega}_1 \times \boldsymbol{\omega}_2
행렬 형태로는 [\mathrm{ad}_{\boldsymbol{\omega}}] = [\boldsymbol{\omega}]_\times이다.
7.4 두 수반 표현의 관계
\mathrm{Ad}_{\exp([\boldsymbol{\omega}]_\times)} = \exp([\boldsymbol{\omega}]_\times) = \mathbf{R}
이는 회전 벡터의 지수가 회전 행렬임을 다시 확인한다.
8. SE(3)의 수반 표현
8.1 행렬 형태
SE(3)의 원소 \mathbf{T} = (\mathbf{R}, \mathbf{p})의 수반 표현은 다음의 6 \times 6 행렬이다.
[\mathrm{Ad}_{\mathbf{T}}] = \begin{bmatrix}\mathbf{R} & \mathbf{0} \\ [\mathbf{p}]_\times\mathbf{R} & \mathbf{R}\end{bmatrix}
이 행렬이 6차원 트위스트에 작용하여 좌표계를 변환한다.
8.2 트위스트의 변환
\mathfrak{se}(3)의 원소(트위스트)가 두 좌표계 사이에서 다음과 같이 변환된다.
\mathcal{V}' = [\mathrm{Ad}_{\mathbf{T}}]\mathcal{V}
여기서 \mathbf{T}는 두 좌표계 사이의 변환이다.
8.3 명시적 변환
트위스트 \mathcal{V} = (\boldsymbol{\omega}, \mathbf{v})가 변환되면
\boldsymbol{\omega}' = \mathbf{R}\boldsymbol{\omega}
\mathbf{v}' = [\mathbf{p}]_\times\mathbf{R}\boldsymbol{\omega} + \mathbf{R}\mathbf{v} = \mathbf{p} \times (\mathbf{R}\boldsymbol{\omega}) + \mathbf{R}\mathbf{v}
이는 회전과 병진이 결합된 트위스트의 좌표계 변환을 보여준다.
8.4 \mathrm{ad} 사상
\mathfrak{se}(3)의 \mathrm{ad} 사상은 6 \times 6 행렬로 표현된다.
[\mathrm{ad}_{\boldsymbol{\xi}}] = \begin{bmatrix}[\boldsymbol{\omega}]_\times & \mathbf{0} \\ [\mathbf{v}]_\times & [\boldsymbol{\omega}]_\times\end{bmatrix}
이 행렬이 트위스트의 리 괄호를 계산한다.
[\mathrm{ad}_{\boldsymbol{\xi}_1}]\boldsymbol{\xi}_2 = [\boldsymbol{\xi}_1, \boldsymbol{\xi}_2]_{\mathfrak{se}(3)}
9. 수반 표현의 성질
9.1 군 동형사상
\mathrm{Ad}는 리 군에서 일반 선형 군으로의 군 동형사상이다.
\mathrm{Ad}_{g_1g_2} = \mathrm{Ad}_{g_1}\mathrm{Ad}_{g_2}
이로부터 다음의 결과들이 따른다.
\mathrm{Ad}_{g^{-1}} = (\mathrm{Ad}_g)^{-1}
\mathrm{Ad}_e = \mathrm{id}
9.2 \mathrm{ad}의 미분 형태
\mathrm{ad}_X는 다음의 미분 방정식을 통해 정의될 수 있다.
\frac{d}{dt}\mathrm{Ad}_{\exp(tX)}(Y)\bigg|_{t=0} = \mathrm{ad}_X(Y) = [X, Y]
이는 \mathrm{Ad}의 무한소 형태가 \mathrm{ad}임을 명확히 보여준다.
9.3 야코비 항등식
야코비 항등식은 \mathrm{ad}의 형태로 다음과 같이 표현된다.
[\mathrm{ad}_X, \mathrm{ad}_Y] = \mathrm{ad}_{[X, Y]}
이는 \mathrm{ad}가 리 대수의 표현임의 본질적 성질이다.
10. 응용
10.1 좌표계 변환
가장 직접적인 응용은 좌표계 변환이다. 한 좌표계에서 측정된 각속도, 트위스트, 자세 오차 등을 다른 좌표계로 변환할 때 수반 표현이 사용된다.
10.2 매니퓰레이터의 자코비안
매니퓰레이터의 자코비안은 관절 속도를 말단 장치의 트위스트로 매핑한다. 자코비안의 열은 각 관절의 트위스트이며, 좌표계에 따라 수반 표현으로 변환된다.
10.2.1 공간 자코비안과 본체 자코비안
공간 자코비안과 본체 자코비안 사이의 변환은 수반 표현으로 이루어진다.
\mathbf{J}_b = [\mathrm{Ad}_{\mathbf{T}_{bs}}]\mathbf{J}_s
여기서 \mathbf{J}_s와 \mathbf{J}_b는 각각 공간과 본체에서의 자코비안이다.
10.3 강체 동역학
강체의 운동 방정식에서 수반 표현이 자연스럽게 등장한다. 트위스트와 렌치의 좌표계 변환에 사용된다.
10.4 자세 추정
자세 추정 알고리즘의 갱신 단계에서 측정 잔차가 한 좌표계에서 다른 좌표계로 변환될 때 수반 표현이 사용된다.
10.5 비선형 최적화
비선형 최적화에서 자세 변수의 야코비안 계산에 \mathrm{Ad}와 \mathrm{ad}가 활용된다. 시각적 SLAM의 번들 조정 등이 대표적이다.
11. 좌측과 우측 사용의 차이
11.1 좌측 곱의 변환
리 군의 비가환성으로 인해 좌측 곱과 우측 곱이 다르며, 이에 따른 변환 공식도 다르다. 예를 들어
\exp(X)\exp(Y) = \exp(\mathrm{Ad}_{\exp(X)}(Y))\exp(X)
이 식은 좌측 곱과 우측 곱을 교환하는 공식이며, 수반 표현이 핵심 역할을 한다.
11.2 활용
이러한 변환 공식은 자세 추정의 곱셈 갱신, 미분 운동학 등에서 유용하다.
12. 수반 표현의 행렬 계산
12.1 효율적인 구현
수반 표현은 행렬 형태로 표현되므로 효율적으로 계산된다. 6 \times 6 행렬의 곱셈으로 트위스트를 변환할 수 있다.
12.2 라이브러리 지원
Sophus, manif 등의 리 군 라이브러리는 수반 표현을 직접 제공한다.
Sophus::SE3d::Adjoint Ad = T.Adj();
Sophus::SE3d::Tangent xi_new = Ad * xi;
12.3 자동 미분
자동 미분 라이브러리는 수반 표현을 사용하여 자세 변수의 야코비안을 효율적으로 계산한다.
13. 수반 표현과 BCH 공식
13.1 BCH 공식의 표현
BCH 공식은 \mathrm{ad}를 사용하여 다음과 같이 표현될 수 있다.
\log(\exp(X)\exp(Y)) = X + \int_0^1 g(\exp(\mathrm{ad}_X)\exp(t\mathrm{ad}_Y))Y\,dt
여기서 g는 어떤 함수이다. 이는 수반 표현이 BCH 공식의 본질에 깊이 관련되어 있음을 보여준다.
13.2 야코비안과의 관계
좌측 야코비안과 우측 야코비안은 \mathrm{ad}의 함수로 표현될 수 있다.
\mathbf{J}_l(X) = \int_0^1\exp(\mathrm{ad}_{tX})\,dt
\mathbf{J}_r(X) = \int_0^1\exp(-\mathrm{ad}_{tX})\,dt
이러한 형태는 야코비안의 일반적 표현이며, 다양한 리 군에서 적용된다.
14. SO(3)의 수반 표현 응용
14.1 본체와 공간 각속도
본체 각속도와 공간 각속도 사이의 변환은 수반 표현으로 이루어진다.
\boldsymbol{\omega}_s = \mathbf{R}\boldsymbol{\omega}_b = \mathrm{Ad}_{\mathbf{R}}(\boldsymbol{\omega}_b)
이는 회전이 한 좌표계에서 다른 좌표계로 각속도를 변환함을 의미한다.
14.2 회전 합성에서의 활용
두 회전의 합성에서 수반 표현이 좌표계 변환의 역할을 한다. 회전 행렬을 직접 다룰 때 자연스럽게 등장한다.
15. SE(3)의 수반 표현 응용
15.1 트위스트의 좌표계 변환
본체 트위스트를 공간 트위스트로 변환하는 데 수반 표현이 사용된다.
\mathcal{V}_s = [\mathrm{Ad}_{\mathbf{T}_{sb}}]\mathcal{V}_b
여기서 \mathbf{T}_{sb}는 본체 좌표계에서 공간 좌표계로의 변환이다.
15.2 렌치의 변환
힘과 토크를 결합한 렌치도 좌표계 변환에서 수반 표현의 변형(transpose)을 사용한다.
\mathcal{F}_s = [\mathrm{Ad}_{\mathbf{T}_{sb}}]^T\mathcal{F}_b
여기서 트랜스포즈는 코트랑겐트 공간의 자연스러운 변환이다.
15.3 매니퓰레이터의 좌표계 변환
매니퓰레이터의 각 링크의 트위스트를 다른 좌표계로 변환할 때 수반 표현이 사용된다.
16. 학습의 가치
수반 표현을 깊이 이해하는 것은 다음과 같은 이점을 제공한다.
- 좌표계 변환의 일반적 원리를 이해할 수 있다.
- 자세 추정 알고리즘의 좌표계 처리를 깊이 이해할 수 있다.
- 매니퓰레이터의 자코비안 변환을 효율적으로 계산할 수 있다.
- 강체 동역학의 트위스트와 렌치의 변환을 자연스럽게 다룰 수 있다.
- 비선형 최적화에서 자세 변수의 야코비안을 정확히 유도할 수 있다.
17. 참고 문헌
- Hall, B. C. (2015). Lie Groups, Lie Algebras, and Representations: An Elementary Introduction (2nd ed.). Springer.
- Stillwell, J. (2008). Naive Lie Theory. Springer.
- 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.
- Selig, J. M. (2005). Geometric Fundamentals of Robotics (2nd ed.). Springer.
- Sola, J., Deray, J., & Atchuthan, D. (2018). “A Micro Lie Theory for State Estimation in Robotics.” arXiv:1812.01537.
version: 1.0