6.122 선형 상미분 방정식의 행렬 지수 해
1. 개요
선형 상미분 방정식(Linear Ordinary Differential Equation, Linear ODE)은 로봇공학에서 선형화된 동역학 모델, 상태 공간 표현, 관측기(observer) 설계 등의 기초를 이룬다. 상수 계수를 갖는 선형 ODE의 해는 행렬 지수 함수를 통해 명시적으로 표현할 수 있다. 본 절에서는 동차 및 비동차 선형 ODE의 행렬 지수 해를 유도하고, 로봇공학에서의 구체적인 응용을 다룬다.
2. 동차 선형 상미분 방정식
2.1 기본 형태와 해
상수 계수 행렬 \mathbf{A} \in \mathbb{R}^{n \times n}를 갖는 동차(homogeneous) 선형 ODE는 다음과 같다.
\dot{\mathbf{x}}(t) = \mathbf{A}\,\mathbf{x}(t), \quad \mathbf{x}(0) = \mathbf{x}_0
여기서 \mathbf{x}(t) \in \mathbb{R}^n은 상태 벡터이다. 이 초기값 문제의 유일한 해는 다음과 같다.
\boxed{\mathbf{x}(t) = e^{t\mathbf{A}}\,\mathbf{x}_0}
2.2 해의 검증
\mathbf{x}(t) = e^{t\mathbf{A}}\,\mathbf{x}_0가 실제로 해임을 직접 검증한다.
초기 조건: \mathbf{x}(0) = e^{0 \cdot \mathbf{A}}\,\mathbf{x}_0 = \mathbf{I}\,\mathbf{x}_0 = \mathbf{x}_0 \checkmark
미분 방정식: 행렬 지수의 미분 성질 \frac{d}{dt}e^{t\mathbf{A}} = \mathbf{A}\,e^{t\mathbf{A}}를 이용하면,
\dot{\mathbf{x}}(t) = \frac{d}{dt}\left(e^{t\mathbf{A}}\,\mathbf{x}_0\right) = \mathbf{A}\,e^{t\mathbf{A}}\,\mathbf{x}_0 = \mathbf{A}\,\mathbf{x}(t) \quad \checkmark
2.3 해의 유일성
피카르-린들뢰프 정리(Picard-Lindelöf theorem)에 의해, \mathbf{f}(\mathbf{x}) = \mathbf{A}\mathbf{x}가 리프시츠(Lipschitz) 조건을 만족하므로(선형 함수는 전역적으로 리프시츠), 해는 전체 시간 축 t \in (-\infty, \infty)에서 유일하다.
3. 상태 전이 행렬
3.1 정의와 성질
행렬 \boldsymbol{\Phi}(t) = e^{t\mathbf{A}}를 상태 전이 행렬(state transition matrix)이라 한다. 이는 초기 상태에서 시간 t 후의 상태로의 선형 사상(linear map)을 정의한다.
상태 전이 행렬은 다음 성질을 갖는다.
성질 1 (초기 조건): \boldsymbol{\Phi}(0) = \mathbf{I}
성질 2 (준군 성질): \boldsymbol{\Phi}(t_1 + t_2) = \boldsymbol{\Phi}(t_1)\boldsymbol{\Phi}(t_2)
이 성질은 e^{(t_1+t_2)\mathbf{A}} = e^{t_1\mathbf{A}}e^{t_2\mathbf{A}}로부터 직접 따른다(t_1\mathbf{A}와 t_2\mathbf{A}는 교환 가능하므로).
성질 3 (역행렬): \boldsymbol{\Phi}(t)^{-1} = \boldsymbol{\Phi}(-t)
성질 4 (행렬식): \det(\boldsymbol{\Phi}(t)) = e^{t\,\text{tr}(\mathbf{A})}
이 성질은 리우빌 공식(Liouville’s formula)이라 하며, 위상 공간의 부피 변화를 기술한다. \text{tr}(\mathbf{A}) = 0이면 부피가 보존되며, 이는 보존계(conservative system)의 특성이다.
3.2 일반 초기 시간
초기 시간이 t_0 \neq 0인 경우의 해는 다음과 같다.
\mathbf{x}(t) = e^{(t - t_0)\mathbf{A}}\,\mathbf{x}(t_0) = \boldsymbol{\Phi}(t - t_0)\,\mathbf{x}(t_0)
4. 비동차 선형 상미분 방정식
4.1 기본 형태
외부 입력 \mathbf{u}(t)가 있는 비동차(nonhomogeneous) 선형 ODE는 다음과 같다.
\dot{\mathbf{x}}(t) = \mathbf{A}\,\mathbf{x}(t) + \mathbf{B}\,\mathbf{u}(t), \quad \mathbf{x}(0) = \mathbf{x}_0
여기서 \mathbf{B} \in \mathbb{R}^{n \times m}은 입력 행렬이고, \mathbf{u}(t) \in \mathbb{R}^m은 입력 벡터이다.
4.2 상수 변화법에 의한 해
해를 \mathbf{x}(t) = e^{t\mathbf{A}}\,\mathbf{c}(t)로 놓는 상수 변화법(variation of constants, variation of parameters)을 적용한다.
양변을 미분하면 다음과 같다.
\dot{\mathbf{x}} = \mathbf{A}\,e^{t\mathbf{A}}\,\mathbf{c}(t) + e^{t\mathbf{A}}\,\dot{\mathbf{c}}(t)
원래 방정식에 대입하면 다음을 얻는다.
\mathbf{A}\,e^{t\mathbf{A}}\,\mathbf{c}(t) + e^{t\mathbf{A}}\,\dot{\mathbf{c}}(t) = \mathbf{A}\,e^{t\mathbf{A}}\,\mathbf{c}(t) + \mathbf{B}\,\mathbf{u}(t)
따라서 다음이 성립한다.
\dot{\mathbf{c}}(t) = e^{-t\mathbf{A}}\,\mathbf{B}\,\mathbf{u}(t)
\mathbf{c}(0) = \mathbf{x}_0을 초기 조건으로 적분하면 다음과 같다.
\mathbf{c}(t) = \mathbf{x}_0 + \int_0^t e^{-\tau\mathbf{A}}\,\mathbf{B}\,\mathbf{u}(\tau)\,d\tau
최종 해는 다음과 같다.
\boxed{\mathbf{x}(t) = e^{t\mathbf{A}}\,\mathbf{x}_0 + \int_0^t e^{(t-\tau)\mathbf{A}}\,\mathbf{B}\,\mathbf{u}(\tau)\,d\tau}
첫째 항은 자유 응답(free response) 또는 영입력 응답(zero-input response)이고, 둘째 항은 강제 응답(forced response) 또는 영상태 응답(zero-state response)이다. 이 적분을 콘볼루션 적분(convolution integral)이라 한다.
4.3 구간 일정 입력의 경우
디지털 제어에서 샘플링 주기 T 동안 입력이 일정한 경우, 즉 \mathbf{u}(\tau) = \mathbf{u}_k (kT \leq \tau < (k+1)T)인 경우, 콘볼루션 적분을 명시적으로 계산할 수 있다.
\mathbf{x}_{k+1} = e^{T\mathbf{A}}\,\mathbf{x}_k + \left(\int_0^T e^{\tau\mathbf{A}}\,d\tau\right)\mathbf{B}\,\mathbf{u}_k
적분을 계산하면 다음과 같다.
\int_0^T e^{\tau\mathbf{A}}\,d\tau = \mathbf{A}^{-1}(e^{T\mathbf{A}} - \mathbf{I})
이 공식은 \mathbf{A}가 가역일 때 유효하다. \mathbf{A}가 특이한 경우에는 급수 형태를 사용한다.
\int_0^T e^{\tau\mathbf{A}}\,d\tau = T\mathbf{I} + \frac{T^2}{2!}\mathbf{A} + \frac{T^3}{3!}\mathbf{A}^2 + \cdots = T\sum_{k=0}^{\infty} \frac{(T\mathbf{A})^k}{(k+1)!}
따라서 이산 시간 상태 공간 모델은 다음과 같다.
\mathbf{x}_{k+1} = \boldsymbol{\Phi}_d\,\mathbf{x}_k + \boldsymbol{\Gamma}_d\,\mathbf{u}_k
여기서 \boldsymbol{\Phi}_d = e^{T\mathbf{A}}이고 \boldsymbol{\Gamma}_d = \mathbf{A}^{-1}(e^{T\mathbf{A}} - \mathbf{I})\mathbf{B}이다.
5. 해의 안정성 분석
5.1 고유값과 안정성
동차 시스템 \dot{\mathbf{x}} = \mathbf{A}\mathbf{x}의 안정성은 \mathbf{A}의 고유값에 의해 완전히 결정된다.
\mathbf{A}의 고유값을 \lambda_i = \alpha_i + j\beta_i라 하면, 해의 각 모드는 e^{\lambda_i t} = e^{\alpha_i t}(\cos\beta_i t + j\sin\beta_i t)와 같은 형태이다.
| 고유값 조건 | 시스템 거동 | 안정성 |
|---|---|---|
| 모든 \alpha_i < 0 | 모든 모드 감쇠 | 점근 안정(asymptotically stable) |
| 어떤 \alpha_i > 0 | 해당 모드 발산 | 불안정(unstable) |
| 모든 \alpha_i \leq 0, 일부 \alpha_i = 0 | 유한 범위 유지 | 한계 안정(marginally stable)* |
*한계 안정은 중복 고유값의 경우 추가 조건이 필요하다.
5.2 행렬 지수의 노름 한계
\mathbf{A}의 스펙트럼 무결점(spectral abscissa) \alpha(\mathbf{A}) = \max_i \text{Re}(\lambda_i)에 대해 다음이 성립한다.
\|e^{t\mathbf{A}}\| \leq C\, e^{\alpha(\mathbf{A})t}
여기서 C는 \mathbf{A}에 의존하는 상수이다. \mathbf{A}가 정규 행렬(normal matrix)이면 C = 1이다.
그러나 비정규(non-normal) 행렬에서는 C \gg 1이 될 수 있으며, 이 경우 t가 작은 동안 \|e^{t\mathbf{A}}\|가 일시적으로 크게 증가하는 과도 성장(transient growth)이 발생할 수 있다.
6. 로봇공학에서의 응용
6.1 선형화된 동역학
비선형 로봇 동역학 \dot{\mathbf{x}} = \mathbf{f}(\mathbf{x}, \mathbf{u})를 평형점 (\mathbf{x}_e, \mathbf{u}_e) 주위에서 선형화하면 다음과 같다.
\delta\dot{\mathbf{x}} = \mathbf{A}\,\delta\mathbf{x} + \mathbf{B}\,\delta\mathbf{u}
여기서 \delta\mathbf{x} = \mathbf{x} - \mathbf{x}_e, \delta\mathbf{u} = \mathbf{u} - \mathbf{u}_e이고,
\mathbf{A} = \frac{\partial \mathbf{f}}{\partial \mathbf{x}}\bigg\vert_{(\mathbf{x}_e, \mathbf{u}_e)}, \quad \mathbf{B} = \frac{\partial \mathbf{f}}{\partial \mathbf{u}}\bigg\vert_{(\mathbf{x}_e, \mathbf{u}_e)}
이 선형화된 시스템의 해가 행렬 지수로 표현되며, 국소적 안정성 분석과 선형 제어기 설계의 기초가 된다.
6.2 관절 PD 제어기의 응답
단일 관절의 PD 제어기가 적용된 선형 모델은 다음과 같다.
m\ddot{q} + d\dot{q} + kq = k\,q_d
이를 상태 공간 형태로 변환하면 \mathbf{x} = (q, \dot{q})^T에 대해 다음과 같다.
\dot{\mathbf{x}} = \begin{bmatrix} 0 & 1 \\ -k/m & -d/m \end{bmatrix}\mathbf{x} + \begin{bmatrix} 0 \\ k/m \end{bmatrix}q_d
시스템 행렬 \mathbf{A}의 고유값은 다음과 같다.
\lambda_{1,2} = \frac{-d \pm \sqrt{d^2 - 4mk}}{2m}
d^2 < 4mk (부족 감쇠)인 경우 고유값은 복소수이며, 해는 감쇠 진동을 보인다.
\mathbf{x}(t) = e^{t\mathbf{A}}\,\mathbf{x}_0 + \mathbf{A}^{-1}(e^{t\mathbf{A}} - \mathbf{I})\begin{bmatrix} 0 \\ k/m \end{bmatrix}q_d
6.3 디지털 제어를 위한 이산화
연속 시간 제어기를 디지털로 구현할 때, 정확한 이산화(exact discretization)에 행렬 지수를 사용한다. 이는 샘플링 주기 내에서 연속 시스템의 거동을 정확히 반영하므로, 영차 홀드(Zero-Order Hold, ZOH) 이산화 중 가장 정확하다.
실용적인 구현에서 \boldsymbol{\Phi}_d와 \boldsymbol{\Gamma}_d를 동시에 계산하기 위해 다음과 같은 확대 행렬(augmented matrix)의 지수를 이용한다.
\exp\left(\begin{bmatrix} \mathbf{A} & \mathbf{B} \\ \mathbf{0} & \mathbf{0} \end{bmatrix} T\right) = \begin{bmatrix} \boldsymbol{\Phi}_d & \boldsymbol{\Gamma}_d \\ \mathbf{0} & \mathbf{I} \end{bmatrix}
이 방법은 한 번의 행렬 지수 계산으로 이산 시간 시스템 행렬과 입력 행렬을 모두 얻을 수 있어 효율적이다.
6.4 강체 운동의 시간 적분
일정한 공간 속도(spatial velocity) \boldsymbol{\mathcal{V}}_s로 운동하는 강체의 시간에 따른 자세 변화는 다음과 같다.
\dot{\mathbf{T}}(t) = [\boldsymbol{\mathcal{V}}_s]\,\mathbf{T}(t)
이 동차 선형 ODE의 해는 다음과 같다.
\mathbf{T}(t) = e^{[\boldsymbol{\mathcal{V}}_s]t}\,\mathbf{T}(0)
여기서 [\boldsymbol{\mathcal{V}}_s] \in \mathfrak{se}(3)는 공간 속도의 행렬 표현이고, e^{[\boldsymbol{\mathcal{V}}_s]t} \in SE(3)는 로드리게스 공식의 확장으로 닫힌 형태로 계산할 수 있다.
이는 일정한 나선 운동(constant screw motion)에 대응하며, 로봇 관절의 기본적인 운동 요소이다.
7. 시변 시스템에 대한 확장
시스템 행렬이 시간에 따라 변하는 경우, 즉 \dot{\mathbf{x}}(t) = \mathbf{A}(t)\mathbf{x}(t)인 경우, 해는 일반적으로 단순한 행렬 지수 형태가 아니다. 이 경우 상태 전이 행렬 \boldsymbol{\Phi}(t, t_0)는 다음과 같은 피노(Peano)-베이커(Baker) 급수로 표현된다.
\boldsymbol{\Phi}(t, t_0) = \mathbf{I} + \int_{t_0}^t \mathbf{A}(\tau_1)\,d\tau_1 + \int_{t_0}^t \mathbf{A}(\tau_1)\int_{t_0}^{\tau_1}\mathbf{A}(\tau_2)\,d\tau_2\,d\tau_1 + \cdots
\mathbf{A}(t_1)과 \mathbf{A}(t_2)가 모든 t_1, t_2에 대해 교환 가능한 특수한 경우에만, 해가 \exp\left(\int_{t_0}^t \mathbf{A}(\tau)\,d\tau\right)의 형태가 된다.
로봇 동역학에서 관성 행렬 \mathbf{M}(\mathbf{q})는 시간에 따라 변하므로, 선형화된 시스템은 일반적으로 시변 시스템이다. 이 경우 각 시간 구간에서 행렬을 일정하다고 근사(동결 계수 근사, frozen coefficient approximation)하여 행렬 지수 해를 적용하는 것이 실용적인 접근법이다.
8. 참고 문헌
- Chen, C. T. (1999). Linear System Theory and Design (3rd ed.). Oxford University Press.
- Ogata, K. (2010). Modern Control Engineering (5th ed.). Prentice Hall.
- 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.
- Golub, G. H., & Van Loan, C. F. (2013). Matrix Computations (4th ed.). Johns Hopkins University Press.
- Moler, C., & Van Loan, C. (2003). “Nineteen Dubious Ways to Compute the Exponential of a Matrix, Twenty-Five Years Later.” SIAM Review, 45(1), 3–49.
- Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
v 0.1