6.107 자코비안의 영 공간과 내부 운동

6.107 자코비안의 영 공간과 내부 운동

1. 영 공간의 정의

행렬 J \in \mathbb{R}^{m \times n}의 영 공간(null space, kernel)은 다음과 같이 정의된다.

\mathcal{N}(J) = \{\mathbf{q} \in \mathbb{R}^n \mid J\mathbf{q} = \mathbf{0}\}

로봇공학에서 자코비안 J(\mathbf{q}) \in \mathbb{R}^{m \times n}은 관절 속도 \dot{\mathbf{q}} \in \mathbb{R}^n과 말단 장치의 작업 공간 속도 \dot{\mathbf{x}} \in \mathbb{R}^m 사이의 관계를 나타낸다.

\dot{\mathbf{x}} = J(\mathbf{q})\dot{\mathbf{q}}

따라서 \mathcal{N}(J)에 속하는 관절 속도 \dot{\mathbf{q}}_{\text{null}}J\dot{\mathbf{q}}_{\text{null}} = \mathbf{0}을 만족하며, 말단 장치의 속도를 전혀 변화시키지 않는 관절 운동을 의미한다.

2. 내부 운동의 개념

정의 6.107.1 (내부 운동). 자코비안의 영 공간에 속하는 관절 속도에 의해 발생하는 운동을 내부 운동(internal motion) 또는 자기 운동(self-motion)이라 한다. 내부 운동은 말단 장치의 위치와 자세를 일정하게 유지하면서 로봇의 내부 형상만을 변화시키는 관절 운동이다.

내부 운동이 존재하기 위해서는 \mathcal{N}(J) \neq \{\mathbf{0}\}이어야 하며, 이는 n > \text{rank}(J)일 때 성립한다. 여유 자유도(redundant degree of freedom) 로봇에서는 관절 자유도 n이 작업 공간 자유도 m보다 큰 경우(n > m)에 해당하므로, \text{rank}(J) \leq m < n일 때 비자명한 영 공간이 항상 존재한다.

3. 영 공간의 차원

랭크-영도 정리(rank-nullity theorem)에 의하여 자코비안의 영 공간 차원은 다음과 같이 결정된다.

\dim(\mathcal{N}(J)) = n - \text{rank}(J)

자코비안이 최대 랭크 \text{rank}(J) = m을 가지는 비특이 형상에서, 영 공간의 차원은 다음과 같다.

\dim(\mathcal{N}(J)) = n - m

이 값은 로봇이 보유하는 여유 자유도의 수와 일치한다. 예를 들어, 7자유도 로봇이 6차원 작업 공간 속도를 제어하는 경우 영 공간의 차원은 7 - 6 = 1이며, 이는 1차원의 내부 운동 매니폴드가 존재함을 의미한다.

4. 영 공간 기저의 계산

자코비안의 영 공간 기저를 구하는 대표적인 방법은 다음과 같다.

4.1 SVD를 이용한 방법

자코비안의 특이값 분해(Singular Value Decomposition)를 수행하면,

J = U\Sigma V^\top

여기서 U \in \mathbb{R}^{m \times m}, \Sigma \in \mathbb{R}^{m \times n}, V \in \mathbb{R}^{n \times n}이며, \text{rank}(J) = r일 때, V의 마지막 (n - r)개 열벡터가 영 공간의 정규 직교 기저를 형성한다.

\mathcal{N}(J) = \text{span}(\mathbf{v}_{r+1}, \mathbf{v}_{r+2}, \ldots, \mathbf{v}_n)

4.2 QR 분해를 이용한 방법

J^\top의 QR 분해를 수행하여 J^\top = QR을 구한 뒤, R의 영이 되는 열에 대응하는 Q의 열벡터로부터 영 공간 기저를 추출할 수 있다. SVD보다 계산 비용이 낮으나, 수치적 안정성에서는 SVD가 더 우수하다.

5. 영 공간과 해의 구조

비동차 방정식 J\dot{\mathbf{q}} = \dot{\mathbf{x}}의 일반해는 특수해와 동차해의 합으로 표현된다.

정리 6.107.1 (일반해의 구조). \dot{\mathbf{x}}J의 열 공간에 속할 때, 방정식 J\dot{\mathbf{q}} = \dot{\mathbf{x}}의 일반해는 다음과 같다.

\dot{\mathbf{q}} = \dot{\mathbf{q}}_p + \dot{\mathbf{q}}_h

여기서 \dot{\mathbf{q}}_p는 임의의 특수해이고, \dot{\mathbf{q}}_h \in \mathcal{N}(J)는 동차해이다.

유사 역행렬(pseudoinverse) J^+를 사용하면 최소 노름 특수해를 구할 수 있으며, 일반해는 다음과 같이 표현된다.

\dot{\mathbf{q}} = J^+\dot{\mathbf{x}} + (I - J^+J)\mathbf{z}

여기서 \mathbf{z} \in \mathbb{R}^n은 임의의 벡터이고, (I - J^+J)는 자코비안의 영 공간으로의 직교 사영 행렬이다.

6. 영 공간 사영 행렬

정의 6.107.2 (영 공간 사영 행렬). 자코비안 J의 영 공간으로의 직교 사영 행렬은 다음과 같이 정의된다.

N = I - J^+J

여기서 J^+ = J^\top(JJ^\top)^{-1} (또는 J가 특이인 경우 무어-펜로즈 유사 역행렬)이다.

정리 6.107.2. 영 공간 사영 행렬 N은 다음 성질을 만족한다.

(i) 멱등성: N^2 = N

(ii) 대칭성: N^\top = N

(iii) 사영 조건: 임의의 \mathbf{z} \in \mathbb{R}^n에 대하여 N\mathbf{z} \in \mathcal{N}(J)

(iv) 불변성: \dot{\mathbf{q}}_h \in \mathcal{N}(J)이면 N\dot{\mathbf{q}}_h = \dot{\mathbf{q}}_h

증명. (i) N^2 = (I - J^+J)(I - J^+J) = I - J^+J - J^+J + J^+JJ^+J이다. 무어-펜로즈 조건에 의하여 JJ^+J = J이므로 J^+JJ^+J = J^+J이 성립한다. 따라서 N^2 = I - J^+J = N이다. (iii) JN\mathbf{z} = J(I - J^+J)\mathbf{z} = J\mathbf{z} - JJ^+J\mathbf{z} = J\mathbf{z} - J\mathbf{z} = \mathbf{0}이므로 N\mathbf{z} \in \mathcal{N}(J)이다. \square

내부 운동의 기하학적 해석

여유 자유도 로봇의 관절 공간에서, 말단 장치가 특정 위치와 자세 \mathbf{x}_0에 대응하는 관절 형상의 집합은 자기 운동 매니폴드(self-motion manifold)를 형성한다.

\mathcal{M}_{\mathbf{x}_0} = \{\mathbf{q} \in \mathbb{R}^n \mid f(\mathbf{q}) = \mathbf{x}_0\}

여기서 f: \mathbb{R}^n \to \mathbb{R}^m은 순기구학 함수이다. 자기 운동 매니폴드의 차원은 일반적으로 n - m이며, 각 점 \mathbf{q}에서의 접선 공간이 바로 \mathcal{N}(J(\mathbf{q}))이다.

이러한 기하학적 구조를 통하여, 영 공간 내에서의 관절 속도는 자기 운동 매니폴드 위를 이동하는 운동으로 해석할 수 있으며, 이는 말단 장치의 상태를 유지하면서 로봇의 내부 형상을 재구성하는 데 활용된다.

7. 내부 운동의 물리적 해석

7.1 팔꿈치 순환 운동

7자유도 로봇 팔의 경우, 말단 장치의 위치와 자세를 고정한 상태에서 팔꿈치가 원형 궤도를 따라 순환하는 운동이 대표적인 내부 운동의 예이다. 이 운동은 1차원 영 공간에 의해 생성되며, 팔꿈치 각도(swivel angle) \phi로 매개변수화할 수 있다.

7.2 관절 한계 회피

내부 운동을 활용하여 관절 변위를 관절 범위의 중앙으로 이동시킬 수 있다. 관절 한계로부터의 거리를 최대화하는 비용 함수의 기울기를 영 공간에 사영함으로써 이를 실현한다.

7.3 특이점 회피

자코비안의 조작성(manipulability) 지표를 증가시키는 방향의 관절 속도를 영 공간에 사영하면, 말단 장치의 운동을 방해하지 않으면서 특이 형상으로부터 멀어지는 내부 운동을 생성할 수 있다.

8. 내부 운동의 존재 조건 정리

조건영 공간내부 운동
n = m이고 \text{rank}(J) = m\mathcal{N}(J) = \{\mathbf{0}\}존재하지 않음
n > m이고 \text{rank}(J) = m\dim(\mathcal{N}(J)) = n - m > 0(n-m)차원
\text{rank}(J) < \min(m, n)\dim(\mathcal{N}(J)) = n - \text{rank}(J)특이 형상에서 증가

9. 수치 예제

3자유도 평면 로봇이 2차원 작업 공간 속도(\dot{x}, \dot{y})를 제어하는 경우를 고려하자. 자코비안이 다음과 같다고 하자.

J = \begin{bmatrix} -1 & -1 & -0.5 \\ 1 & 0.5 & 0 \end{bmatrix}

이 자코비안의 랭크는 2이므로, 영 공간의 차원은 3 - 2 = 1이다. J\mathbf{v} = \mathbf{0}을 풀면 영 공간 기저를 구할 수 있다.

\begin{bmatrix} -1 & -1 & -0.5 \\ 1 & 0.5 & 0 \end{bmatrix} \begin{bmatrix} v_1 \\ v_2 \\ v_3 \end{bmatrix} = \begin{bmatrix} 0 \\ 0 \end{bmatrix}

두 번째 행으로부터 v_1 = -0.5 v_2이고, 첫 번째 행에 대입하면 0.5 v_2 - v_2 - 0.5 v_3 = 0, 즉 v_3 = -v_2이다. v_2 = 2로 놓으면 \mathbf{v} = (-1, 2, -2)^\top이 영 공간의 기저 벡터이다.

정규화하면,

\hat{\mathbf{v}} = \frac{1}{3}(-1, 2, -2)^\top

이 방향의 관절 속도는 말단 장치를 움직이지 않으면서 로봇의 내부 형상을 변화시키는 내부 운동을 생성한다.


참고문헌

  • Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
  • Nakamura, Y. (1991). Advanced Robotics: Redundancy and Optimization. Addison-Wesley.
  • Strang, G. (2023). Introduction to Linear Algebra (6th ed.). Wellesley-Cambridge Press.
  • Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.

v 0.1