6.76 회전 행렬과 각속도 벡터의 관계

1. 도입

강체의 자세는 회전 행렬로 표현되며, 자세의 시간 변화율은 각속도 벡터로 표현된다. 회전 행렬과 각속도 벡터는 서로 독립적인 개념이 아니라, 회전 행렬의 시간 미분을 통하여 자연스럽게 연결되는 한 쌍의 객체이다. 이 관계는 단순히 운동학의 시간 미분을 형식적으로 다루는 데 그치지 않고, 회전 행렬의 집합 SO(3) 가 가지는 리 군 구조와 그 접공간에 해당하는 리 대수 \mathfrak{so}(3) 의 본질을 드러내는 핵심적 관계이다. 본 절에서는 회전 행렬의 시간 미분으로부터 각속도가 어떻게 정의되는지, 반대칭 행렬과 각속도 벡터의 동형 관계, 세계 좌표계와 물체 좌표계에서의 표현 차이, 그리고 로봇 공학에서의 활용을 학술적으로 기술한다.

2. 회전 행렬의 시간 미분과 반대칭 행렬

2.1 직교성 조건의 미분

시간에 따라 변화하는 회전 행렬 R(t) \in SO(3) 는 모든 시각에서 직교성 조건을 만족한다.

R(t)^{T} R(t) = I

양변을 시간 t 에 대하여 미분하면 다음을 얻는다.

\dot{R}(t)^{T} R(t) + R(t)^{T} \dot{R}(t) = 0

이는 곧 다음과 동치이다.

\left( R(t)^{T} \dot{R}(t) \right)^{T} + R(t)^{T} \dot{R}(t) = 0

따라서 행렬 R^{T} \dot{R} 는 반대칭 행렬(skew-symmetric matrix)이며, 이를 [\boldsymbol{\omega}^{B}]_{\times} 로 표기한다. 여기서 \boldsymbol{\omega}^{B} 는 물체 좌표계에서 표현된 각속도 벡터이다. 마찬가지로 \dot{R} R^{T} 도 반대칭 행렬이며, 이는 세계 좌표계에서 표현된 각속도 벡터에 대응하는 반대칭 행렬 [\boldsymbol{\omega}^{S}]_{\times} 이다.

2.2 반대칭 행렬과 벡터의 동형

3차원에서 반대칭 행렬은 벡터와 일대일 대응 관계를 가진다. 벡터 \boldsymbol{\omega} = [\omega_{x}, \omega_{y}, \omega_{z}]^{T} 에 대응하는 반대칭 행렬은 다음과 같이 정의된다.

[\boldsymbol{\omega}]_{\times} = \begin{bmatrix} 0 & -\omega_{z} & \omega_{y} \\ \omega_{z} & 0 & -\omega_{x} \\ -\omega_{y} & \omega_{x} & 0 \end{bmatrix}

이 사상은 \mathbb{R}^{3}3 \times 3 반대칭 행렬의 집합 \mathfrak{so}(3) 사이의 선형 동형(linear isomorphism)이며, 다음과 같은 핵심적인 성질을 만족한다.

[\boldsymbol{\omega}]_{\times} \mathbf{v} = \boldsymbol{\omega} \times \mathbf{v}

즉 반대칭 행렬을 임의의 벡터에 곱하는 것은 벡터곱(외적) 연산과 동일하다. 이 동형 관계는 회전 운동학에서 행렬 표현과 벡터 표현 사이를 자유롭게 오갈 수 있게 해주는 핵심 도구이다.

3. 각속도의 두 가지 표현

3.1 물체 좌표계 각속도

R(t)^{T} \dot{R}(t) = [\boldsymbol{\omega}^{B}]_{\times} 의 양변에 좌측에서 R(t) 를 곱하면 다음을 얻는다.

\dot{R}(t) = R(t) [\boldsymbol{\omega}^{B}(t)]_{\times}

여기서 \boldsymbol{\omega}^{B} 는 물체에 고정된 좌표계(body frame)에서 측정된 각속도 벡터이며, 자이로스코프와 같이 강체에 부착된 센서가 측정하는 양에 해당한다.

3.2 세계 좌표계 각속도

마찬가지로 \dot{R}(t) R(t)^{T} = [\boldsymbol{\omega}^{S}]_{\times} 의 양변에 우측에서 R(t) 를 곱하면 다음을 얻는다.

\dot{R}(t) = [\boldsymbol{\omega}^{S}(t)]_{\times} R(t)

여기서 \boldsymbol{\omega}^{S} 는 고정된 세계 좌표계(spatial frame)에서 표현된 각속도 벡터이다. 외부 관찰자가 강체의 회전을 보는 관점에서의 각속도가 이에 해당한다.

3.3 두 표현 사이의 변환

두 각속도 표현은 동일한 물리적 회전을 서로 다른 좌표계에서 기술한 것이며, 다음과 같은 회전 변환 관계로 연결된다.

\boldsymbol{\omega}^{S} = R \, \boldsymbol{\omega}^{B}

이는 다음의 항등식으로부터 유도된다.

[\boldsymbol{\omega}^{S}]_{\times} = R [\boldsymbol{\omega}^{B}]_{\times} R^{T}

여기서 좌변과 우변이 모두 반대칭 행렬임을 이용하고, 회전에 의한 반대칭 행렬의 켤레 작용이 곧 그 안의 벡터에 대한 회전 작용임을 적용하면 결과가 따라온다. 이 관계는 자이로 측정값과 외부 기준 좌표계의 각속도 사이를 변환할 때 핵심적으로 사용된다.

4. 회전 운동학 미분 방정식

4.1 자세 운동학 방정식

회전 행렬과 각속도의 관계는 강체의 자세 운동학을 지배하는 일차 미분 방정식으로 정리된다.

\dot{R}(t) = R(t) [\boldsymbol{\omega}^{B}(t)]_{\times} \quad \text{또는} \quad \dot{R}(t) = [\boldsymbol{\omega}^{S}(t)]_{\times} R(t)

이는 회전 행렬의 9개 성분에 대한 행렬 미분 방정식이지만, 직교성 제약에 의해 실제로는 3개의 자유도만을 가진다. 이러한 구조는 SO(3) 가 3차원 매끄러운 다양체이며 그 접공간이 \mathfrak{so}(3) 와 동형이라는 사실을 그대로 반영한다.

4.2 일정 각속도에 대한 해

각속도가 시간에 따라 일정한 경우, 자세 운동학 방정식의 해는 행렬 지수 함수로 주어진다.

R(t) = R(0) \, \exp\!\left( [\boldsymbol{\omega}^{B}]_{\times} \, t \right)

여기서 \exp 는 행렬 지수 함수이며, 반대칭 행렬의 지수가 회전 행렬이 된다는 사실은 로드리게스 공식(Rodrigues’ rotation formula)으로 닫힌 형태로 주어진다. 이 결과는 회전 행렬이 본질적으로 각속도 벡터의 적분으로부터 생성됨을 보여주며, 리 군과 리 대수 사이의 지수 사상의 가장 기본적인 사례가 된다.

5. 리 군적 해석

5.1 SO(3)\mathfrak{so}(3) 의 관계

회전 행렬의 집합 SO(3) 는 콤팩트 리 군이며, 항등원에서의 접공간이 곧 반대칭 행렬의 공간 \mathfrak{so}(3) 이다. 회전 행렬의 시간 미분 \dot{R}SO(3) 위의 곡선 R(t) 에 대한 접벡터이며, 이를 좌측 또는 우측 평행이동을 통하여 항등원에서의 접공간으로 끌어내리면 반대칭 행렬을 얻는다. 두 가지 평행이동 방법이 곧 물체 좌표계 표현과 세계 좌표계 표현에 대응한다.

5.2 각속도와 리 대수 원소의 동일성

각속도 벡터 \boldsymbol{\omega}\mathfrak{so}(3) 의 원소를 \mathbb{R}^{3} 의 벡터로 식별한 것이며, 이 식별은 리 괄호와 벡터 외적 사이의 일치를 보장한다.

[[\boldsymbol{\omega}_{1}]_{\times}, [\boldsymbol{\omega}_{2}]_{\times}] = [\boldsymbol{\omega}_{1} \times \boldsymbol{\omega}_{2}]_{\times}

이 관계는 \mathfrak{so}(3) 가 외적 연산을 곱셈으로 가지는 3차원 리 대수임을 의미하며, 회전 운동학의 비가환성을 정량적으로 다루는 출발점이 된다.

6. 회전 행렬의 미소 변화

6.1 차 근사와 미소 회전

미소 시간 \Delta t 동안의 회전 행렬 변화는 1차 테일러 근사로 다음과 같이 표현된다.

R(t + \Delta t) \approx R(t) \left( I + [\boldsymbol{\omega}^{B}(t)]_{\times} \Delta t \right)

이 근사는 짧은 시간 간격에 대한 자세 갱신의 기본 형태이며, 직관적으로는 미소 회전이 단위 행렬에 반대칭 보정 항을 더한 형태로 표현됨을 의미한다. 그러나 이러한 1차 근사는 SO(3) 위에 있지 않으므로, 누적 사용 시 직교성 손상을 야기한다.

6.2 지수 사상을 통한 정확한 갱신

수치적으로 직교성을 보존하기 위해서는 지수 사상을 활용한 갱신이 사용된다.

R(t + \Delta t) = R(t) \, \exp\!\left( [\boldsymbol{\omega}^{B}(t)]_{\times} \Delta t \right)

이 갱신식은 SO(3) 위의 정확한 한 걸음 적분(exact one-step integration)이며, 시간 간격에 관계없이 회전 행렬의 직교성과 행렬식 조건을 정확히 보존한다.

7. 로봇 공학에서의 활용

7.1 자이로스코프 측정값의 적분

로봇과 무인기에 탑재되는 자이로스코프는 물체 좌표계에서의 각속도 \boldsymbol{\omega}^{B} 를 직접 측정한다. 자세를 추정하기 위해서는 이 각속도 측정값을 회전 행렬에 대한 시간 적분으로 변환해야 하며, 이때 사용되는 관계가 바로 \dot{R} = R [\boldsymbol{\omega}^{B}]_{\times} 이다. 적분 정확도와 직교성 보존 사이의 균형은 자세 추정 알고리듬의 핵심 설계 요소가 된다.

7.2 매니퓰레이터의 말단 각속도 계산

다관절 매니퓰레이터에서 각 관절의 회전 행렬과 그 시간 미분을 누적하면 말단 장치의 각속도를 계산할 수 있다. 이 계산은 자코비안 행렬의 회전 부분을 구성하는 핵심 절차이며, 회전 행렬과 각속도 벡터의 관계가 직접 활용된다.

7.3 강체 동역학에서의 회전 운동학

강체의 회전 운동 방정식은 오일러 방정식(Euler’s equations)으로 표현되며, 그 우변에 등장하는 외력 토크와 좌변의 각운동량 변화는 모두 각속도와 회전 행렬의 관계에 기반하여 정의된다. 강체의 자세 미분 방정식과 동역학 방정식을 결합하여 시뮬레이션을 수행할 때, 회전 행렬과 각속도의 일관된 좌표계 정의는 정확한 결과를 위한 필수 조건이다.

7.4 시각-관성 항법과 자세 추정

카메라와 관성 측정 장치를 결합한 시각-관성 항법(visual-inertial odometry) 시스템에서는 자이로 각속도를 적분하여 자세를 예측하고, 이를 시각 측정값으로 보정하는 절차가 반복된다. 이 과정 전반에서 회전 행렬과 각속도 벡터의 관계는 예측 단계의 자세 전파, 공분산 전파, 자코비안 계산 등 거의 모든 단계에 등장하며, 그 정확한 처리는 추정 정확도에 결정적인 영향을 미친다.

7.5 자세 제어기 설계

강체의 자세를 원하는 목표 자세로 수렴시키는 제어기에서는 자세 오차와 그 시간 미분이 제어 입력으로 사용된다. 회전 행렬 사이의 오차를 반대칭 행렬을 거쳐 벡터로 환원하고, 각속도와의 관계를 이용하여 비례-미분 제어 법칙을 구성하는 절차는 자세 제어의 표준적 방법이며, 이 모든 과정의 수학적 기반이 회전 행렬과 각속도 벡터의 관계이다.

8. 결론

회전 행렬의 시간 미분은 직교성 조건의 미분으로부터 자연스럽게 반대칭 행렬을 산출하며, 이 반대칭 행렬은 각속도 벡터와 일대일로 대응한다. 물체 좌표계와 세계 좌표계에서의 두 가지 표현은 회전 변환을 통하여 연결되며, 이는 좌측 평행이동과 우측 평행이동이라는 리 군 위의 두 가지 자연스러운 작용에 대응한다. 회전 행렬과 각속도 벡터의 관계는 자세 운동학 미분 방정식을 정의하고, 자이로 측정의 적분, 매니퓰레이터 자코비안 계산, 강체 동역학, 자세 추정과 제어 등 로봇 공학의 핵심 절차 전반의 수학적 토대가 된다. 이 관계에 대한 명확한 이해는 회전을 다루는 모든 알고리듬의 정확성과 일관성을 확보하기 위한 필수 조건이다.


참고문헌

  • 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.
  • Spong, M. W., Hutchinson, S., & Vidyasagar, M. (2020). Robot Modeling and Control (2nd ed.). Wiley.
  • Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
  • Craig, J. J. (2005). Introduction to Robotics: Mechanics and Control (3rd ed.). Pearson.
  • Selig, J. M. (2005). Geometric Fundamentals of Robotics (2nd ed.). Springer.
  • Bullo, F., & Lewis, A. D. (2005). Geometric Control of Mechanical Systems. Springer.
  • Hall, B. C. (2015). Lie Groups, Lie Algebras, and Representations: An Elementary Introduction (2nd ed.). Springer.
  • Bloch, A. M. (2003). Nonholonomic Mechanics and Control. Springer.
  • Shuster, M. D. (1993). “A survey of attitude representations.” Journal of the Astronautical Sciences, 41(4), 439–517.

Version: 1.0