9.62 트위스트(Twist)의 정의와 수학적 표현
1. 트위스트의 개념
트위스트(twist)는 강체의 무한소 운동(infinitesimal motion)을 표현하는 6차원 벡터이다. 강체가 한 순간에 가지는 각속도와 선형 속도를 결합한 양이며, 스크류 운동의 무한소 형태이다. 트위스트는 SE(3)의 리 대수 \mathfrak{se}(3)의 원소로서, 매니퓰레이터 기구학과 동역학의 핵심 개념이다.
2. 트위스트의 형식적 정의
트위스트는 6차원 벡터로 다음과 같이 정의된다.
\boldsymbol{\xi} = \begin{bmatrix}\boldsymbol{\omega} \\ \mathbf{v}\end{bmatrix} \in \mathbb{R}^6
여기서
- \boldsymbol{\omega} \in \mathbb{R}^3: 각속도 부분(angular velocity)
- \mathbf{v} \in \mathbb{R}^3: 선형 속도 부분(linear velocity)
이 두 3차원 벡터의 결합이 6차원 트위스트를 형성한다.
3. 트위스트의 두 가지 표현
트위스트는 어느 좌표계에서 표현되는지에 따라 두 가지로 구분된다.
3.1 공간 트위스트(Spatial Twist)
공간 좌표계(또는 월드 좌표계)에서 표현되는 트위스트이다.
\mathcal{V}_s = \begin{bmatrix}\boldsymbol{\omega}_s \\ \mathbf{v}_s\end{bmatrix}
여기서 \boldsymbol{\omega}_s는 공간 좌표계에서의 각속도, \mathbf{v}_s는 공간 좌표계의 원점을 따라가는 강체 위 점의 선형 속도이다. \mathbf{v}_s는 강체의 질량 중심이나 다른 특정 점의 속도가 아니라, 공간 좌표계의 원점에 위치한 가상의 점이 강체와 함께 움직이면서 가지는 속도이다.
3.2 본체 트위스트(Body Twist)
본체 좌표계에서 표현되는 트위스트이다.
\mathcal{V}_b = \begin{bmatrix}\boldsymbol{\omega}_b \\ \mathbf{v}_b\end{bmatrix}
여기서 \boldsymbol{\omega}_b는 본체 좌표계에서의 각속도, \mathbf{v}_b는 본체 좌표계의 원점의 선형 속도(본체 좌표계에서 표현)이다.
4. 두 표현 사이의 변환
공간 트위스트와 본체 트위스트는 동일한 강체 운동을 다른 좌표계에서 표현한 것이다. 두 표현 사이의 변환은 공역(adjoint) 사상을 사용한다.
\mathcal{V}_s = \mathrm{Ad}_{\mathbf{T}}\mathcal{V}_b, \quad \mathcal{V}_b = \mathrm{Ad}_{\mathbf{T}^{-1}}\mathcal{V}_s
여기서 \mathbf{T} = (\mathbf{R}, \mathbf{t})는 공간 좌표계에서 본체 좌표계로의 변환 행렬이며, 공역은 다음과 같이 정의된다.
\mathrm{Ad}_{\mathbf{T}} = \begin{bmatrix}\mathbf{R} & \mathbf{0} \\ [\mathbf{t}]_\times\mathbf{R} & \mathbf{R}\end{bmatrix} \in \mathbb{R}^{6 \times 6}
이 6 \times 6 행렬이 트위스트의 좌표계 변환을 수행한다.
5. 트위스트의 행렬 표현
트위스트는 4 \times 4 반대칭 행렬로 표현될 수 있다.
[\boldsymbol{\xi}] = \begin{bmatrix}[\boldsymbol{\omega}]_\times & \mathbf{v} \\ \mathbf{0}^T & 0\end{bmatrix} \in \mathbb{R}^{4 \times 4}
여기서 [\boldsymbol{\omega}]_\times는 각속도 벡터의 3 \times 3 반대칭 행렬이다. 이 행렬 표현이 \mathfrak{se}(3)의 원소이며, SE(3)의 동차 변환 행렬과 같은 차원을 가진다.
5.1 해트 연산자
벡터에서 행렬로의 사상 (\cdot)^\wedge를 정의한다.
\boldsymbol{\xi}^\wedge = [\boldsymbol{\xi}] = \begin{bmatrix}[\boldsymbol{\omega}]_\times & \mathbf{v} \\ \mathbf{0}^T & 0\end{bmatrix}
5.2 벡터 연산자
행렬에서 벡터로의 역사상 (\cdot)^\vee도 정의된다.
([\boldsymbol{\xi}])^\vee = \boldsymbol{\xi}
두 연산자는 서로의 역함수이며, 6차원 벡터 공간 \mathbb{R}^6과 4차원 반대칭 행렬 공간 \mathfrak{se}(3) 사이의 동형 사상을 제공한다.
6. 트위스트의 기하학적 해석
6.1 스크류 매개변수와의 연결
트위스트의 두 부분 \boldsymbol{\omega}와 \mathbf{v}는 스크류 운동의 매개변수와 다음과 같이 연결된다.
\boldsymbol{\omega} = \dot{\phi}\hat{\mathbf{s}}
\mathbf{v} = -\dot{\phi}(\hat{\mathbf{s}} \times \mathbf{q}) + \dot{d}\hat{\mathbf{s}}
여기서 \hat{\mathbf{s}}는 스크류 축의 방향, \mathbf{q}는 축 위의 한 점, \dot{\phi}는 회전 속도, \dot{d}는 병진 속도이다.
이는 다음과 같이 해석된다. 각속도 \boldsymbol{\omega}는 스크류 축의 방향과 회전 속도를 담고 있다. 선형 속도 \mathbf{v}는 두 부분의 합인데, 첫 번째 항 -\dot{\phi}(\hat{\mathbf{s}} \times \mathbf{q})는 스크류 축이 원점에서 떨어져 있음에 따른 원점의 회전 운동, 두 번째 항 \dot{d}\hat{\mathbf{s}}는 축 방향의 직접적 병진이다.
6.2 피치의 추출
트위스트의 피치는 다음과 같이 계산된다.
h = \frac{\boldsymbol{\omega}^T\mathbf{v}}{\lVert \boldsymbol{\omega} \rVert^2}
이는 각속도 방향으로의 선형 속도 성분(즉, 축에 평행한 진행 속도)을 회전 속도의 제곱으로 나눈 값이다.
6.3 스크류 축의 추출
트위스트로부터 스크류 축의 방향과 위치는 다음과 같이 계산된다.
\hat{\mathbf{s}} = \frac{\boldsymbol{\omega}}{\lVert \boldsymbol{\omega} \rVert}, \quad \mathbf{q} = \frac{\boldsymbol{\omega} \times \mathbf{v}}{\lVert \boldsymbol{\omega} \rVert^2}
7. 트위스트와 강체 속도
트위스트의 본질적 의미는 “강체의 6차원 속도“이다. 즉, 한 순간에 강체가 어떻게 움직이고 있는지를 6개의 숫자로 완전히 기술한다.
7.1 회전 부분 \boldsymbol{\omega}
각속도 벡터로, 단위는 라디안/초이다. 방향이 회전 축, 크기가 회전 속도이다.
7.2 병진 부분 \mathbf{v}
선형 속도 벡터로, 단위는 미터/초이다. 다만 어느 점의 속도인지에 따라 의미가 다르다.
- 공간 트위스트의 \mathbf{v}_s: 공간 좌표계 원점에 가상으로 위치한 강체상의 점의 속도
- 본체 트위스트의 \mathbf{v}_b: 본체 좌표계 원점의 속도(본체 좌표계에서 표현)
8. 트위스트와 미분의 관계
강체 변환 \mathbf{T}(t)의 시간 미분과 트위스트의 관계는 다음과 같다.
8.1 공간 트위스트
[\mathcal{V}_s] = \dot{\mathbf{T}}\mathbf{T}^{-1}
8.2 본체 트위스트
[\mathcal{V}_b] = \mathbf{T}^{-1}\dot{\mathbf{T}}
이 두 식은 트위스트가 회전 행렬의 시간 미분 공식 \dot{\mathbf{R}} = [\boldsymbol{\omega}]_\times\mathbf{R} 또는 \dot{\mathbf{R}} = \mathbf{R}[\boldsymbol{\omega}]_\times의 6차원 일반화임을 보여준다.
9. 트위스트와 지수 사상
트위스트로부터 강체 변환을 계산하는 것은 행렬 지수 함수를 통해 이루어진다.
\mathbf{T}(t) = \exp(t[\boldsymbol{\xi}])
여기서 [\boldsymbol{\xi}]는 트위스트의 4 \times 4 반대칭 행렬 표현이다. 이 지수 사상이 \mathfrak{se}(3)에서 SE(3)로의 사상이며, 닫힌 형태로 표현된다.
9.1 닫힌 형태
\exp([\boldsymbol{\xi}]) = \begin{bmatrix}\exp([\boldsymbol{\omega}]_\times) & \mathbf{J}_l(\boldsymbol{\omega})\mathbf{v} \\ \mathbf{0}^T & 1\end{bmatrix}
여기서 \exp([\boldsymbol{\omega}]_\times)는 로드리게스 공식에 의한 회전 행렬, \mathbf{J}_l(\boldsymbol{\omega})는 좌측 야코비안이다.
좌측 야코비안의 닫힌 형태는
\mathbf{J}_l(\boldsymbol{\omega}) = \mathbf{I} + \frac{1 - \cos\phi}{\phi^2}[\boldsymbol{\omega}]_\times + \frac{\phi - \sin\phi}{\phi^3}[\boldsymbol{\omega}]_\times^2
이며, \phi = \lVert \boldsymbol{\omega} \rVert이다.
10. 트위스트의 응용
10.1 매니퓰레이터 자코비안
매니퓰레이터의 자코비안 행렬 \mathbf{J}(\boldsymbol{\theta})는 관절 각속도 \dot{\boldsymbol{\theta}}를 말단 장치의 트위스트 \mathcal{V}로 매핑한다.
\mathcal{V} = \mathbf{J}(\boldsymbol{\theta})\dot{\boldsymbol{\theta}}
자코비안의 각 열은 한 관절의 스크류 축에 해당한다.
10.2 POE 공식
곱지수 공식에서 매니퓰레이터의 순기구학은 트위스트의 지수의 곱으로 표현된다.
\mathbf{T}(\boldsymbol{\theta}) = e^{[\boldsymbol{\xi}_1]\theta_1}e^{[\boldsymbol{\xi}_2]\theta_2}\cdots e^{[\boldsymbol{\xi}_n]\theta_n}\mathbf{M}
각 \boldsymbol{\xi}_i가 한 관절의 스크류 축(트위스트 형태)이다.
10.3 자세 추정과 SLAM
확장 칼만 필터의 SE(3) 변형이나 그래프 SLAM에서 자세의 작은 변화를 트위스트로 표현하고, 지수 사상으로 자세를 갱신한다.
10.4 동역학
매니퓰레이터의 동역학에서 각 링크의 트위스트와 가속도가 독립 변수로 사용된다. Featherstone의 articulated body algorithm은 트위스트와 렌치(wrench)의 개념을 활용한다.
10.5 운동 명령
로봇의 카르테시안 운동 명령은 트위스트로 직접 지정될 수 있다. 예를 들어 “회전 축 z 주위로 0.5 rad/s, 동시에 x 방향으로 0.1 m/s 이동“이라는 명령이 트위스트로 표현된다.
11. 트위스트와 다른 표현법의 비교
| 표현법 | 차원 | 용도 |
|---|---|---|
| 트위스트 (공간 또는 본체) | 6 | 강체 속도, 매니퓰레이터 자코비안 |
| 트위스트의 반대칭 행렬 | 4 \times 4 | 지수 사상, 동차 변환 미분 |
| 회전 행렬 미분 | 3 \times 3 | 회전만의 운동 |
| 위치 미분 | 3 | 병진만의 운동 |
트위스트는 6차원 벡터로서 가장 간결하면서도 강체 운동을 완전히 기술한다.
12. 참고 문헌
- 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.
- Featherstone, R. (2008). Rigid Body Dynamics Algorithms. Springer.
- 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