6.88 자코비안 행렬의 시간 미분

자코비안 행렬은 관절 변수의 함수이므로 로봇이 운동하는 동안 시간에 따라 변화한다. 자코비안의 시간 미분 \dot{J}(\mathbf{q})는 가속도 수준의 기구학 관계 및 동역학 방정식에서 핵심적인 역할을 한다. 본 절에서는 자코비안 시간 미분의 수학적 유도, 계산 방법, 그리고 물리적 의미를 다룬다.

1. 가속도 관계에서의 자코비안 시간 미분

미분 기구학의 속도 관계 \dot{\mathbf{x}} = J(\mathbf{q}) \dot{\mathbf{q}}를 시간에 대해 미분하면 가속도 관계를 얻는다.

\ddot{\mathbf{x}} = J(\mathbf{q}) \, \ddot{\mathbf{q}} + \dot{J}(\mathbf{q}) \, \dot{\mathbf{q}}

여기서 \ddot{\mathbf{x}} \in \mathbb{R}^m는 작업 공간 가속도 벡터, \ddot{\mathbf{q}} \in \mathbb{R}^n는 관절 가속도 벡터이다. 제1항 J \ddot{\mathbf{q}}는 관절 가속도에 의한 기여이고, 제2항 \dot{J} \dot{\mathbf{q}}는 관절 속도에 의한 비선형적 기여로서 구심 가속도와 코리올리 가속도 효과를 포함한다.

2. 연쇄 법칙에 의한 일반적 유도

자코비안 J(\mathbf{q})의 각 성분 J_{ij}가 관절 변수 \mathbf{q}의 함수이므로, 연쇄 법칙에 의해 시간 미분은 다음과 같이 계산된다.

\dot{J}(\mathbf{q}) = \sum_{k=1}^{n} \frac{\partial J}{\partial q_k} \dot{q}_k

성분별로 표현하면 다음과 같다.

\dot{J}_{ij} = \sum_{k=1}^{n} \frac{\partial J_{ij}}{\partial q_k} \dot{q}_k

이 계산에는 자코비안의 각 성분에 대한 편미분, 즉 순기구학 함수의 2차 편미분(헤시안)이 필요하다.

\frac{\partial J_{ij}}{\partial q_k} = \frac{\partial^2 f_i}{\partial q_j \partial q_k}

3. 기하학적 자코비안의 열 벡터 시간 미분

기하학적 자코비안의 i번째 열 벡터 \mathbf{j}_i의 시간 미분은 관절 유형에 따라 다음과 같이 유도된다.

3.1 회전 관절의 열 벡터 시간 미분

i번째 관절이 회전 관절인 경우, 열 벡터는 \mathbf{j}_i = [\mathbf{z}_{i-1} \times (\mathbf{p}_n - \mathbf{p}_{i-1}), \; \mathbf{z}_{i-1}]^\top이다. 각 성분의 시간 미분을 구한다.

각속도 성분의 시간 미분:

\dot{\mathbf{z}}_{i-1} = \boldsymbol{\omega}_{i-1} \times \mathbf{z}_{i-1}

여기서 \boldsymbol{\omega}_{i-1}은 링크 i-1의 각속도 벡터이다. 이는 회전하는 강체에 부착된 벡터의 시간 미분에 대한 기본 공식이다.

선속도 성분의 시간 미분:

레버 암 벡터를 \mathbf{r}_i = \mathbf{p}_n - \mathbf{p}_{i-1}으로 정의하면, 선속도 성분의 시간 미분은 곱의 미분법에 의해 다음과 같다.

\frac{d}{dt}\left(\mathbf{z}_{i-1} \times \mathbf{r}_i\right) = \dot{\mathbf{z}}_{i-1} \times \mathbf{r}_i + \mathbf{z}_{i-1} \times \dot{\mathbf{r}}_i

여기서 \dot{\mathbf{r}}_i = \dot{\mathbf{p}}_n - \dot{\mathbf{p}}_{i-1} = \mathbf{v}_n - \mathbf{v}_{i-1}이다. \mathbf{v}_n은 말단 장치 원점의 선속도, \mathbf{v}_{i-1}은 좌표계 \{i-1\} 원점의 선속도이다.

이를 정리하면 다음과 같다.

\frac{d}{dt}\left(\mathbf{z}_{i-1} \times \mathbf{r}_i\right) = (\boldsymbol{\omega}_{i-1} \times \mathbf{z}_{i-1}) \times \mathbf{r}_i + \mathbf{z}_{i-1} \times (\mathbf{v}_n - \mathbf{v}_{i-1})

3.2 직동 관절의 열 벡터 시간 미분

i번째 관절이 직동 관절인 경우, 열 벡터는 \mathbf{j}_i = [\mathbf{z}_{i-1}, \; \mathbf{0}]^\top이다. 시간 미분은 다음과 같다.

\dot{\mathbf{j}}_i = \begin{bmatrix} \dot{\mathbf{z}}_{i-1} \\ \mathbf{0} \end{bmatrix} = \begin{bmatrix} \boldsymbol{\omega}_{i-1} \times \mathbf{z}_{i-1} \\ \mathbf{0} \end{bmatrix}

4. \dot{J}\dot{\mathbf{q}} 항의 직접 계산

실제 구현에서는 \dot{J}를 명시적으로 구성한 후 \dot{\mathbf{q}}와 곱하는 것보다, \dot{J}\dot{\mathbf{q}} 벡터를 직접 계산하는 것이 더 효율적이다. 이를 위해 각 관절의 열 벡터 시간 미분에 해당 관절 속도를 곱하여 합산한다.

\dot{J} \dot{\mathbf{q}} = \sum_{i=1}^{n} \dot{\mathbf{j}}_i \dot{q}_i

또한 다음의 등가적 표현이 자주 사용된다. 작업 공간 가속도에서 \dot{J}\dot{\mathbf{q}} 항을 분리하면 다음과 같다.

\dot{J}\dot{\mathbf{q}} = \ddot{\mathbf{x}} - J \ddot{\mathbf{q}}

이 관계는 작업 공간 제어에서 피드포워드 보상항을 계산하는 데 활용된다.

5. 수치적 계산 방법

5.1 유한 차분에 의한 근사

해석적 유도가 복잡한 경우, 자코비안의 시간 미분을 수치적으로 근사할 수 있다. 현재 시각 t에서의 자코비안 J(t)와 이전 시각 t - \Delta t에서의 자코비안 J(t - \Delta t)를 이용하여 후방 차분(backward difference)으로 근사한다.

\dot{J}(t) \approx \frac{J(t) - J(t - \Delta t)}{\Delta t}

이 방법은 구현이 간단하나, 시간 간격 \Delta t의 선택에 민감하며 수치적 잡음(noise)에 취약하다.

5.2 편미분에 의한 해석적 계산

자코비안 성분의 편미분을 해석적으로 구한 후 연쇄 법칙을 적용하는 방법이다. i번째 열의 j번째 관절에 대한 편미분은 다음과 같다.

회전 관절 i와 관절 j (j \leq i)에 대해, 선속도 성분의 편미분은 다음과 같이 표현된다.

\frac{\partial}{\partial q_j}\left(\mathbf{z}_{i-1} \times (\mathbf{p}_n - \mathbf{p}_{i-1})\right) = \frac{\partial \mathbf{z}_{i-1}}{\partial q_j} \times (\mathbf{p}_n - \mathbf{p}_{i-1}) + \mathbf{z}_{i-1} \times \left(\frac{\partial \mathbf{p}_n}{\partial q_j} - \frac{\partial \mathbf{p}_{i-1}}{\partial q_j}\right)

이 편미분들은 이미 계산된 자코비안의 열 벡터로부터 추출할 수 있다.

6. 동역학에서의 역할

자코비안의 시간 미분은 작업 공간에서 표현된 동역학 방정식에서 중요한 역할을 한다. 관절 공간의 운동 방정식을 작업 공간으로 변환하면 다음과 같다.

M_x(\mathbf{q}) \ddot{\mathbf{x}} + C_x(\mathbf{q}, \dot{\mathbf{q}}) \dot{\mathbf{x}} + \mathbf{g}_x(\mathbf{q}) = \mathbf{F}

여기서 작업 공간 관성 행렬 M_x와 코리올리-구심력 행렬 C_x는 자코비안과 그 시간 미분을 포함하여 다음과 같이 표현된다.

M_x = J^{-\top} M(\mathbf{q}) J^{-1}

C_x = J^{-\top}\left(C(\mathbf{q}, \dot{\mathbf{q}}) - M(\mathbf{q}) J^{-1} \dot{J}\right) J^{-1}

여기서 M(\mathbf{q})는 관절 공간 관성 행렬, C(\mathbf{q}, \dot{\mathbf{q}})는 관절 공간 코리올리-구심력 행렬이다.

7. 작업 공간 제어에서의 활용

작업 공간에서의 역동역학 제어(inverse dynamics control)를 구현할 때, 원하는 작업 공간 가속도 \ddot{\mathbf{x}}_d를 관절 가속도 명령으로 변환하여야 한다.

\ddot{\mathbf{q}}_d = J^{-1}(\ddot{\mathbf{x}}_d - \dot{J}\dot{\mathbf{q}})

여기서 \dot{J}\dot{\mathbf{q}}는 비선형 보상항으로서, 이를 정확하게 계산하지 않으면 궤적 추종 성능이 저하된다. 따라서 \dot{J}\dot{\mathbf{q}}의 효율적이고 정확한 계산은 실시간 로봇 제어에서 중요한 실용적 과제이다.

8. 계산 효율성

\dot{J}의 완전한 행렬을 구성하려면 6 \times n개의 성분 각각에 대해 n개의 편미분을 계산해야 하므로 O(6n^2)의 연산량이 필요하다. 그러나 작업 공간 제어에서 실제로 필요한 것은 \dot{J}\dot{\mathbf{q}} \in \mathbb{R}^6 벡터이므로, 이를 직접 계산하면 O(6n)의 연산량으로 줄일 수 있다. 재귀적(recursive) 알고리즘을 활용하면 순방향 속도 전파 과정에서 \dot{J}\dot{\mathbf{q}}를 자연스럽게 얻을 수 있어 추가 연산 없이 효율적으로 계산할 수 있다.


9. 참고 문헌

  • 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 Prentice Hall.
  • Spong, M. W., Hutchinson, S., & Vidyasagar, M. (2006). Robot Modeling and Control. John Wiley & Sons.
  • Featherstone, R. (2008). Rigid Body Dynamics Algorithms. Springer.
  • Lynch, K. M., & Park, F. C. (2017). Modern Robotics: Mechanics, Planning, and Control. Cambridge University Press.

v 0.1