6.8 벡터의 외적과 법선 벡터

1. 외적의 정의

외적(cross product) 또는 벡터곱(vector product)은 3차원 공간에서 두 벡터로부터 또 하나의 벡터를 생성하는 이항 연산이다. 외적은 내적과 달리 벡터를 결과로 반환하며, 이 결과 벡터는 두 입력 벡터가 만드는 평면에 수직인 방향을 가진다. 외적은 로봇공학에서 토크 계산, 각속도와 선속도의 관계, 평면 법선 벡터의 도출, 회전 행렬의 시간 미분 등에 본질적으로 사용된다.

정의 6.8.1 (외적). \mathbb{R}^3의 두 벡터 \mathbf{a} = (a_1, a_2, a_3)^\top\mathbf{b} = (b_1, b_2, b_3)^\top의 외적 \mathbf{a} \times \mathbf{b}는 다음과 같이 정의된다.

\mathbf{a} \times \mathbf{b} = \begin{bmatrix} a_2 b_3 - a_3 b_2 \\ a_3 b_1 - a_1 b_3 \\ a_1 b_2 - a_2 b_1 \end{bmatrix}

이 정의는 다음과 같이 행렬식 형태로 표현되기도 한다.

\mathbf{a} \times \mathbf{b} = \det\begin{bmatrix} \mathbf{e}_1 & \mathbf{e}_2 & \mathbf{e}_3 \\ a_1 & a_2 & a_3 \\ b_1 & b_2 & b_3 \end{bmatrix}

여기서 \mathbf{e}_1, \mathbf{e}_2, \mathbf{e}_3는 표준 기저 벡터이다.

2. 외적의 기하학적 성질

정리 6.8.1. 외적 \mathbf{a} \times \mathbf{b}는 다음 세 가지 기하학적 성질을 만족한다.

  1. 수직성: \mathbf{a} \times \mathbf{b}\mathbf{a}\mathbf{b} 모두에 수직이다.
    (\mathbf{a} \times \mathbf{b}) \cdot \mathbf{a} = 0, \quad (\mathbf{a} \times \mathbf{b}) \cdot \mathbf{b} = 0

  2. 크기: \mathbf{a}\mathbf{b}의 사잇각을 \theta라 하면,
    \|\mathbf{a} \times \mathbf{b}\| = \|\mathbf{a}\| \|\mathbf{b}\| \sin\theta
    이며, 이는 \mathbf{a}\mathbf{b}가 만드는 평행 사변형의 면적과 같다.

  3. 방향: \mathbf{a} \times \mathbf{b}의 방향은 오른손 법칙(right-hand rule)에 의해 결정된다. 오른손의 손가락을 \mathbf{a}에서 \mathbf{b}로 감을 때 엄지손가락이 가리키는 방향이 \mathbf{a} \times \mathbf{b}의 방향이다.

3. 외적의 대수적 성질

임의의 벡터 \mathbf{a}, \mathbf{b}, \mathbf{c} \in \mathbb{R}^3와 스칼라 k \in \mathbb{R}에 대하여 다음이 성립한다.

(C1) 반교환 법칙(Anti-commutativity): \mathbf{a} \times \mathbf{b} = -(\mathbf{b} \times \mathbf{a})

(C2) 분배 법칙(Distributivity): \mathbf{a} \times (\mathbf{b} + \mathbf{c}) = \mathbf{a} \times \mathbf{b} + \mathbf{a} \times \mathbf{c}

(C3) 스칼라 곱과의 결합: (k\mathbf{a}) \times \mathbf{b} = \mathbf{a} \times (k\mathbf{b}) = k(\mathbf{a} \times \mathbf{b})

(C4) 자기 외적의 영성: \mathbf{a} \times \mathbf{a} = \mathbf{0}

(C5) 영벡터와의 외적: \mathbf{a} \times \mathbf{0} = \mathbf{0}

특히 외적은 결합 법칙을 만족하지 않는다. 일반적으로 (\mathbf{a} \times \mathbf{b}) \times \mathbf{c} \neq \mathbf{a} \times (\mathbf{b} \times \mathbf{c})이다. 두 표현 사이의 관계는 야코비 항등식(Jacobi identity)으로 기술된다.

\mathbf{a} \times (\mathbf{b} \times \mathbf{c}) + \mathbf{b} \times (\mathbf{c} \times \mathbf{a}) + \mathbf{c} \times (\mathbf{a} \times \mathbf{b}) = \mathbf{0}

표준 기저 벡터의 외적

\mathbb{R}^3의 표준 기저 벡터 \mathbf{e}_1, \mathbf{e}_2, \mathbf{e}_3의 외적은 다음과 같다.

\mathbf{e}_1 \times \mathbf{e}_2 = \mathbf{e}_3, \quad \mathbf{e}_2 \times \mathbf{e}_3 = \mathbf{e}_1, \quad \mathbf{e}_3 \times \mathbf{e}_1 = \mathbf{e}_2

이는 우수 좌표계(right-handed coordinate system)의 특성이며, 좌수 좌표계(left-handed coordinate system)에서는 부호가 반대로 된다.

4. 외적과 반대칭 행렬

외적 연산은 반대칭 행렬(skew-symmetric matrix)을 이용한 행렬-벡터 곱으로 표현할 수 있다. 벡터 \mathbf{a} = (a_1, a_2, a_3)^\top에 대하여 다음의 반대칭 행렬을 정의한다.

[\mathbf{a}]_\times = \begin{bmatrix} 0 & -a_3 & a_2 \\ a_3 & 0 & -a_1 \\ -a_2 & a_1 & 0 \end{bmatrix}

이 행렬을 사용하면 외적은 다음과 같이 표현된다.

\mathbf{a} \times \mathbf{b} = [\mathbf{a}]_\times \mathbf{b}

이 표기법은 로봇공학에서 매우 중요하며, 회전 행렬과 각속도의 관계, 리 군 SO(3)와 리 대수 so(3)의 관계, 강체 동역학의 표현 등에 본질적으로 사용된다.

반대칭 행렬은 다음의 성질을 만족한다.

[\mathbf{a}]_\times^\top = -[\mathbf{a}]_\times

또한 [\mathbf{a}]_\times \mathbf{a} = \mathbf{0}이며, 이는 벡터 \mathbf{a} 자신이 [\mathbf{a}]_\times의 영 공간에 속함을 의미한다.

레비-치비타 기호를 이용한 표현

레비-치비타 기호(Levi-Civita symbol) \epsilon_{ijk}를 이용하면 외적의 제i 성분은 다음과 같이 표현된다.

(\mathbf{a} \times \mathbf{b})_i = \sum_{j=1}^{3} \sum_{k=1}^{3} \epsilon_{ijk} a_j b_k

여기서 \epsilon_{ijk}는 다음과 같이 정의된다.

\epsilon_{ijk} = \begin{cases} +1 & (i,j,k) \text{가 } (1,2,3) \text{의 짝순열} \\ -1 & (i,j,k) \text{가 } (1,2,3) \text{의 홀순열} \\ 0 & \text{두 지표가 동일한 경우} \end{cases}

이 표기법은 텐서 해석에서 외적을 일반화하고 좌표 변환 규칙을 명확히 하는 데 사용된다.

평면의 법선 벡터

3차원 공간에서 두 벡터 \mathbf{a}\mathbf{b}가 만드는 평면의 법선 벡터(normal vector)는 외적 \mathbf{a} \times \mathbf{b}로 직접 계산된다. 단위 법선 벡터(unit normal vector) \hat{\mathbf{n}}은 다음과 같이 정규화된다.

\hat{\mathbf{n}} = \frac{\mathbf{a} \times \mathbf{b}}{\|\mathbf{a} \times \mathbf{b}\|}

세 점 P_1, P_2, P_3로 정의되는 평면의 법선은 두 변 벡터 \mathbf{v}_1 = P_2 - P_1\mathbf{v}_2 = P_3 - P_1의 외적으로 계산할 수 있다.

\hat{\mathbf{n}} = \frac{(P_2 - P_1) \times (P_3 - P_1)}{\|(P_2 - P_1) \times (P_3 - P_1)\|}

평면의 방정식

평면 위의 한 점 P_0 = (x_0, y_0, z_0)와 법선 벡터 \mathbf{n} = (n_x, n_y, n_z)^\top가 주어지면, 평면 위의 임의의 점 P = (x, y, z)는 다음 조건을 만족한다.

\mathbf{n} \cdot (P - P_0) = 0

이를 전개하면 평면의 일반 방정식을 얻는다.

n_x(x - x_0) + n_y(y - y_0) + n_z(z - z_0) = 0

외적의 미분

시간에 의존하는 두 벡터 \mathbf{a}(t)\mathbf{b}(t)의 외적의 시간 미분은 다음과 같이 계산된다.

\frac{d}{dt}(\mathbf{a} \times \mathbf{b}) = \frac{d\mathbf{a}}{dt} \times \mathbf{b} + \mathbf{a} \times \frac{d\mathbf{b}}{dt}

이는 일반적인 곱의 미분 법칙(product rule)과 동일한 형태이며, 외적의 비교환성 때문에 항의 순서가 보존되어야 한다.

5. 로봇공학에서의 응용

5.1 토크의 계산

물체의 위치 벡터 \mathbf{r}에 작용하는 힘 \mathbf{f}가 만드는 토크(moment of force) \boldsymbol{\tau}는 외적으로 정의된다.

\boldsymbol{\tau} = \mathbf{r} \times \mathbf{f}

토크의 크기는 \|\boldsymbol{\tau}\| = \|\mathbf{r}\| \|\mathbf{f}\| \sin\theta이며, 여기서 \theta는 위치 벡터와 힘 벡터의 사잇각이다. 토크의 방향은 회전축의 방향을 나타낸다.

선속도와 각속도의 관계

강체가 각속도 \boldsymbol{\omega}로 회전할 때, 회전축으로부터 위치 \mathbf{r}에 있는 점의 선속도 \mathbf{v}는 다음과 같이 외적으로 표현된다.

\mathbf{v} = \boldsymbol{\omega} \times \mathbf{r}

이 관계는 강체 운동학의 가장 기본적인 식 중 하나이며, 로봇 매니퓰레이터의 자코비안 계산과 동역학 해석에 본질적으로 사용된다.

5.2 회전 행렬의 시간 미분

회전 행렬 R(t) \in SO(3)의 시간 미분은 각속도 벡터 \boldsymbol{\omega}의 반대칭 행렬과의 곱으로 표현된다.

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

이 식은 회전의 동역학을 기술하는 핵심 관계식이며, 자세 추정과 자세 제어의 수학적 기반이다.

자코비안 행렬의 구성

회전 관절(revolute joint)에 대한 자코비안의 열벡터는 외적을 사용하여 다음과 같이 계산된다.

J_i = \begin{bmatrix} \mathbf{z}_{i-1} \times (\mathbf{p}_e - \mathbf{p}_{i-1}) \\ \mathbf{z}_{i-1} \end{bmatrix}

여기서 \mathbf{z}_{i-1}i번째 관절축의 단위 벡터, \mathbf{p}_{i-1}i번째 관절의 위치, \mathbf{p}_e는 말단 장치의 위치이다. 외적은 관절축에 대한 회전이 말단 장치 위치에 미치는 선속도 기여를 계산한다.

5.3 표면 법선과 충돌 검출

3차원 객체의 표면에서 법선 벡터는 외적으로 계산된다. 삼각형 메시(triangular mesh)에서 각 삼각형의 법선은 두 변 벡터의 외적으로 얻어지며, 충돌 검출과 접촉 역학에서 접촉 평면을 정의하는 데 사용된다. 점-평면 거리 계산, 광선-삼각형 교차 판정 등도 외적을 통해 효율적으로 수행된다.

5.4 자세 오차의 정의

회전 행렬 R_d (목표 자세)와 R (현재 자세) 사이의 자세 오차는 다음과 같이 정의될 수 있다.

\mathbf{e}_R = \frac{1}{2} \sum_{i=1}^{3} \mathbf{r}_i \times \mathbf{r}_{di}

여기서 \mathbf{r}_i\mathbf{r}_{di}는 각각 RR_d의 제i 열벡터이다. 이 오차 벡터는 자세 제어기의 입력으로 사용된다.


참고문헌

  • 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.
  • 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.

Version: 1.0