6.104 영 공간의 정의와 계산
1. 개요
영 공간(null space, 핵(kernel))은 선형대수학의 기본 개념 중 하나로, 행렬로 표현되는 선형 사상에서 영벡터로 사상되는 모든 벡터의 집합이다. 로봇공학에서 영 공간은 야코비안의 영 공간을 통해 여유 자유도(redundancy)를 활용하는 데 핵심적인 역할을 한다. 이 절에서는 영 공간의 수학적 정의, 계산 방법, 그리고 로봇공학에서의 의미를 상세히 다룬다.
2. 영 공간의 정의
2.1 일반 정의
행렬 \mathbf{A} \in \mathbb{R}^{m \times n}에 대해 영 공간 \mathcal{N}(\mathbf{A})는 다음과 같이 정의된다.
\mathcal{N}(\mathbf{A}) = \{ \mathbf{x} \in \mathbb{R}^n \mid \mathbf{A}\mathbf{x} = \mathbf{0} \}
즉, \mathbf{A}에 의해 영벡터로 사상되는 \mathbb{R}^n의 모든 벡터의 집합이다.
2.2 부분공간 성질
\mathcal{N}(\mathbf{A})는 \mathbb{R}^n의 부분공간(subspace)이다. 이를 확인하기 위해 다음 세 조건을 검증한다.
- 영벡터 포함: \mathbf{A}\mathbf{0} = \mathbf{0}이므로 \mathbf{0} \in \mathcal{N}(\mathbf{A})이다.
- 덧셈에 대한 닫힘: \mathbf{x}_1, \mathbf{x}_2 \in \mathcal{N}(\mathbf{A})이면 \mathbf{A}(\mathbf{x}_1 + \mathbf{x}_2) = \mathbf{A}\mathbf{x}_1 + \mathbf{A}\mathbf{x}_2 = \mathbf{0}이므로 \mathbf{x}_1 + \mathbf{x}_2 \in \mathcal{N}(\mathbf{A})이다.
- 스칼라 곱에 대한 닫힘: \mathbf{x} \in \mathcal{N}(\mathbf{A})이고 c \in \mathbb{R}이면 \mathbf{A}(c\mathbf{x}) = c\mathbf{A}\mathbf{x} = \mathbf{0}이므로 c\mathbf{x} \in \mathcal{N}(\mathbf{A})이다.
2.3 널리티 (Nullity)
영 공간의 차원을 널리티(nullity)라 하고 다음과 같이 표기한다.
\text{nullity}(\mathbf{A}) = \dim(\mathcal{N}(\mathbf{A}))
3. 영 공간의 계산 방법
3.1 방법 1: 가우스 소거법
\mathbf{A}\mathbf{x} = \mathbf{0}의 해를 구하기 위해 \mathbf{A}를 행 사다리꼴 형태(Row Echelon Form, REF) 또는 기약 행 사다리꼴 형태(Reduced Row Echelon Form, RREF)로 변환한다.
단계:
- \mathbf{A}에 행 연산을 적용하여 RREF를 구한다.
- 피벗 열(pivot column)과 자유 변수(free variable)에 해당하는 열을 식별한다.
- 자유 변수를 매개변수로 설정하고, 피벗 변수를 자유 변수로 표현한다.
- 일반해를 기저 벡터들의 선형 결합으로 표현한다.
예제: 다음 행렬의 영 공간을 구하라.
\mathbf{A} = \begin{bmatrix} 1 & 2 & 3 \\ 2 & 4 & 6 \end{bmatrix}
RREF로 변환하면
\text{RREF}(\mathbf{A}) = \begin{bmatrix} 1 & 2 & 3 \\ 0 & 0 & 0 \end{bmatrix}
피벗 열은 1열이고, 자유 변수는 x_2와 x_3이다. x_2 = s, x_3 = t로 놓으면 x_1 = -2s - 3t이므로
\mathbf{x} = s \begin{bmatrix} -2 \\ 1 \\ 0 \end{bmatrix} + t \begin{bmatrix} -3 \\ 0 \\ 1 \end{bmatrix}
따라서 \mathcal{N}(\mathbf{A})의 기저는 \left\{ \begin{bmatrix} -2 \\ 1 \\ 0 \end{bmatrix}, \begin{bmatrix} -3 \\ 0 \\ 1 \end{bmatrix} \right\}이고 \text{nullity}(\mathbf{A}) = 2이다.
3.2 방법 2: 특이값 분해 (SVD)
\mathbf{A} = \mathbf{U} \boldsymbol{\Sigma} \mathbf{V}^\top의 SVD에서, \text{rank}(\mathbf{A}) = r이면 \mathbf{V}의 마지막 n - r개의 열벡터가 \mathcal{N}(\mathbf{A})의 정규 직교 기저를 형성한다.
\mathcal{N}(\mathbf{A}) = \text{span}\{\mathbf{v}_{r+1}, \mathbf{v}_{r+2}, \dots, \mathbf{v}_n\}
증명: i > r이면 \sigma_i = 0이므로
\mathbf{A}\mathbf{v}_i = \mathbf{U}\boldsymbol{\Sigma}\mathbf{V}^\top \mathbf{v}_i = \mathbf{U}\boldsymbol{\Sigma}\mathbf{e}_i = \sigma_i \mathbf{u}_i = \mathbf{0}
따라서 \mathbf{v}_i \in \mathcal{N}(\mathbf{A})이다. \{\mathbf{v}_{r+1}, \dots, \mathbf{v}_n\}은 정규 직교이므로 일차 독립이고, 개수가 n - r = \text{nullity}(\mathbf{A})개이므로 기저를 형성한다.
3.3 방법 3: QR 분해
열 피벗팅을 적용한 QR 분해 \mathbf{A}\mathbf{P} = \mathbf{Q}\mathbf{R}에서, \mathbf{R}의 대각 원소가 0인 열에 대응하는 \mathbf{P}의 열들로부터 영 공간의 기저를 구성할 수 있다. 이 방법은 SVD보다 계산 비용이 적다.
4. 영 공간 사영 행렬
4.1 정의
영 공간으로의 직교 사영(orthogonal projection) 행렬은 다음과 같이 정의된다.
\mathbf{N} = \mathbf{I} - \mathbf{A}^+ \mathbf{A}
여기서 \mathbf{A}^+는 Moore-Penrose 의사 역행렬이다.
4.2 성질
영 공간 사영 행렬 \mathbf{N}은 다음 성질을 만족한다.
- 멱등성: \mathbf{N}^2 = \mathbf{N}
- 대칭성: \mathbf{N}^\top = \mathbf{N}
- 사영 성질: 임의의 \mathbf{z} \in \mathbb{R}^n에 대해 \mathbf{A}(\mathbf{N}\mathbf{z}) = \mathbf{0}
- 고정점 성질: \mathbf{x} \in \mathcal{N}(\mathbf{A})이면 \mathbf{N}\mathbf{x} = \mathbf{x}
성질 1의 증명:
\mathbf{N}^2 = (\mathbf{I} - \mathbf{A}^+\mathbf{A})(\mathbf{I} - \mathbf{A}^+\mathbf{A}) = \mathbf{I} - 2\mathbf{A}^+\mathbf{A} + \mathbf{A}^+\mathbf{A}\mathbf{A}^+\mathbf{A}
Moore-Penrose 조건 \mathbf{A}^+\mathbf{A}\mathbf{A}^+ = \mathbf{A}^+에 의해 \mathbf{A}^+\mathbf{A}\mathbf{A}^+\mathbf{A} = \mathbf{A}^+\mathbf{A}이므로
\mathbf{N}^2 = \mathbf{I} - 2\mathbf{A}^+\mathbf{A} + \mathbf{A}^+\mathbf{A} = \mathbf{I} - \mathbf{A}^+\mathbf{A} = \mathbf{N}
성질 3의 증명:
\mathbf{A}\mathbf{N}\mathbf{z} = \mathbf{A}(\mathbf{I} - \mathbf{A}^+\mathbf{A})\mathbf{z} = \mathbf{A}\mathbf{z} - \mathbf{A}\mathbf{A}^+\mathbf{A}\mathbf{z}
Moore-Penrose 조건 \mathbf{A}\mathbf{A}^+\mathbf{A} = \mathbf{A}에 의해
\mathbf{A}\mathbf{N}\mathbf{z} = \mathbf{A}\mathbf{z} - \mathbf{A}\mathbf{z} = \mathbf{0}
4.3 SVD를 이용한 표현
SVD에서 \mathbf{A}^+ \mathbf{A} = \mathbf{V}_r \mathbf{V}_r^\top이므로 (\mathbf{V}_r은 \mathbf{V}의 처음 r개 열)
\mathbf{N} = \mathbf{I} - \mathbf{V}_r \mathbf{V}_r^\top = \mathbf{V}_0 \mathbf{V}_0^\top
여기서 \mathbf{V}_0 = [\mathbf{v}_{r+1}, \dots, \mathbf{v}_n]은 영 공간의 정규 직교 기저이다.
5. 로봇공학에서의 영 공간
5.1 야코비안의 영 공간
로봇 매니퓰레이터에서 야코비안 \mathbf{J} \in \mathbb{R}^{m \times n}의 영 공간은
\mathcal{N}(\mathbf{J}) = \{ \dot{\boldsymbol{\theta}} \in \mathbb{R}^n \mid \mathbf{J} \dot{\boldsymbol{\theta}} = \mathbf{0} \}
으로 정의된다. 물리적으로 이는 말단 장치의 속도를 발생시키지 않으면서 관절이 움직이는 내부 운동(self-motion)에 해당한다.
5.2 여유 자유도의 정량화
m < n인 여유 자유도 로봇에서, 풀 랭크일 때
\dim(\mathcal{N}(\mathbf{J})) = n - m
이다. 예를 들어, 7자유도 로봇의 6차원 태스크에서는 \dim(\mathcal{N}(\mathbf{J})) = 1이므로 1차원의 자기 운동 자유도가 존재한다.
5.3 영 공간을 이용한 부가 목적 최적화
의사 역행렬 해에 영 공간 성분을 추가하여 부가 목적을 달성한다.
\dot{\boldsymbol{\theta}} = \mathbf{J}^+ \dot{\mathbf{x}}_d + (\mathbf{I} - \mathbf{J}^+ \mathbf{J}) \dot{\boldsymbol{\theta}}_0
영 공간 사영 (\mathbf{I} - \mathbf{J}^+ \mathbf{J}) \dot{\boldsymbol{\theta}}_0는 주 태스크(\mathbf{J} \dot{\boldsymbol{\theta}} = \dot{\mathbf{x}}_d)에 영향을 주지 않으면서 관절 공간에서의 부가 목적을 추구한다.
경사 하강법(gradient descent)을 적용하여 스칼라 목적 함수 H(\boldsymbol{\theta})를 최대화하고자 하면
\dot{\boldsymbol{\theta}}_0 = k \nabla_{\boldsymbol{\theta}} H(\boldsymbol{\theta})
로 설정한다.
5.4 전형적인 부가 목적 함수
관절 한계 회피:
H(\boldsymbol{\theta}) = -\frac{1}{2n} \sum_{i=1}^{n} \left( \frac{\theta_i - \bar{\theta}_i}{\theta_{i,\max} - \theta_{i,\min}} \right)^2
여기서 \bar{\theta}_i = (\theta_{i,\max} + \theta_{i,\min})/2는 i번째 관절의 중앙값이다.
조작도 최대화:
H(\boldsymbol{\theta}) = \sqrt{\det(\mathbf{J}(\boldsymbol{\theta}) \mathbf{J}(\boldsymbol{\theta})^\top)}
6. 좌영 공간
행렬 \mathbf{A}의 좌영 공간(left null space)은 \mathbf{A}^\top의 영 공간으로 정의된다.
\mathcal{N}(\mathbf{A}^\top) = \{ \mathbf{y} \in \mathbb{R}^m \mid \mathbf{A}^\top \mathbf{y} = \mathbf{0} \}
이는 \mathbf{A}의 열 공간(column space)에 직교하는 부분공간이다.
\mathcal{N}(\mathbf{A}^\top) = \mathcal{C}(\mathbf{A})^{\perp}
여기서 \mathcal{C}(\mathbf{A}) = \{ \mathbf{A}\mathbf{x} \mid \mathbf{x} \in \mathbb{R}^n \}은 \mathbf{A}의 열 공간이다.
로봇공학에서 \mathcal{N}(\mathbf{J}^\top)은 야코비안의 열 공간에 직교하는 태스크 공간 방향, 즉 어떤 관절 토크로도 발생시킬 수 없는 태스크 공간 힘/모멘트 방향을 나타낸다.
7. 네 가지 기본 부분공간의 관계
행렬 \mathbf{A} \in \mathbb{R}^{m \times n}에 대해 네 가지 기본 부분공간은 다음과 같다.
| 부분공간 | 기호 | 공간 | 차원 |
|---|---|---|---|
| 열 공간 | \mathcal{C}(\mathbf{A}) | \mathbb{R}^m | r |
| 행 공간 | \mathcal{C}(\mathbf{A}^\top) | \mathbb{R}^n | r |
| 영 공간 | \mathcal{N}(\mathbf{A}) | \mathbb{R}^n | n - r |
| 좌영 공간 | \mathcal{N}(\mathbf{A}^\top) | \mathbb{R}^m | m - r |
직교 분해 관계:
\mathbb{R}^n = \mathcal{C}(\mathbf{A}^\top) \oplus \mathcal{N}(\mathbf{A})
\mathbb{R}^m = \mathcal{C}(\mathbf{A}) \oplus \mathcal{N}(\mathbf{A}^\top)
8. 참고 문헌
- Strang, G. (2016). Introduction to Linear Algebra (5th ed.). Wellesley-Cambridge Press.
- Nakamura, Y. (1991). Advanced Robotics: Redundancy and Optimization. Addison-Wesley.
- Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
- Golub, G. H., & Van Loan, C. F. (2013). Matrix Computations (4th ed.). Johns Hopkins University Press.
- Lay, D. C., Lay, S. R., & McDonald, J. J. (2016). Linear Algebra and Its Applications (5th ed.). Pearson.
v 0.1