9.63 렌치(Wrench)의 정의와 쌍대 관계

1. 렌치의 개념

렌치(wrench)는 강체에 작용하는 일반화된 힘을 6차원 벡터로 표현한 것이다. 강체에 가해지는 힘과 모멘트를 결합한 양이며, 트위스트(강체의 6차원 속도)와 쌍대 관계(dual relationship)를 가진다. 렌치는 매니퓰레이터의 정역학(statics)과 동역학(dynamics)에서 핵심 개념이다.

2. 렌치의 형식적 정의

렌치는 6차원 벡터로 다음과 같이 정의된다.

\mathcal{F} = \begin{bmatrix}\mathbf{m} \\ \mathbf{f}\end{bmatrix} \in \mathbb{R}^6

또는 일부 문헌에서는 순서를 바꿔서 다음과 같이 표기한다.

\mathcal{F} = \begin{bmatrix}\mathbf{f} \\ \mathbf{m}\end{bmatrix}

여기서

  • \mathbf{f} \in \mathbb{R}^3: 힘 부분(force)
  • \mathbf{m} \in \mathbb{R}^3: 모멘트 부분(moment 또는 torque)

이 두 3차원 벡터의 결합이 6차원 렌치를 형성한다. 표기 순서는 문헌에 따라 다르나, 본 절에서는 모멘트가 먼저 오는 표기를 사용한다.

3. 렌치의 두 가지 표현

트위스트와 마찬가지로 렌치도 어느 좌표계에서 표현되는지에 따라 두 가지로 구분된다.

3.1 공간 렌치(Spatial Wrench)

공간 좌표계에서 표현되는 렌치이다. 모멘트는 공간 좌표계의 원점을 기준으로 측정된다.

\mathcal{F}_s = \begin{bmatrix}\mathbf{m}_s \\ \mathbf{f}_s\end{bmatrix}

3.2 본체 렌치(Body Wrench)

본체 좌표계에서 표현되는 렌치이다. 모멘트는 본체 좌표계의 원점을 기준으로 측정된다.

\mathcal{F}_b = \begin{bmatrix}\mathbf{m}_b \\ \mathbf{f}_b\end{bmatrix}

4. 두 표현 사이의 변환

공간 렌치와 본체 렌치 사이의 변환은 공역 사상의 전치를 사용한다.

\mathcal{F}_b = \mathrm{Ad}_{\mathbf{T}}^T\mathcal{F}_s

여기서 \mathrm{Ad}_{\mathbf{T}}^T는 공역 사상의 전치이다. 트위스트의 변환에서 사용되는 \mathrm{Ad}_{\mathbf{T}}의 전치가 렌치 변환에 사용되며, 이는 두 양의 쌍대성을 반영한다.

5. 트위스트와 렌치의 쌍대 관계

트위스트 \mathcal{V}와 렌치 \mathcal{F}는 6차원 벡터 공간 \mathbb{R}^6에서 쌍대 공간(dual space)의 관계를 가진다. 이 쌍대성은 다음의 내적으로 표현된다.

\mathcal{P} = \mathcal{F}^T\mathcal{V} = \mathbf{m}^T\boldsymbol{\omega} + \mathbf{f}^T\mathbf{v}

이 내적의 물리적 의미는 **순간 일률(instantaneous power)**이다. 즉, 강체에 작용하는 렌치와 강체의 트위스트의 내적이 그 순간에 강체에 전달되는 일률(에너지/시간)이다.

5.1 일률의 두 항

위 식의 두 항은 각각 다음을 의미한다.

  • \mathbf{m}^T\boldsymbol{\omega}: 모멘트와 각속도의 내적, 즉 회전에 의한 일률
  • \mathbf{f}^T\mathbf{v}: 힘과 선형 속도의 내적, 즉 병진에 의한 일률

두 항의 합이 강체에 전달되는 총 일률이다.

6. 쌍대성의 좌표 불변성

트위스트-렌치 내적은 좌표 변환에 대해 불변이다. 공간 좌표계에서

\mathcal{P} = \mathcal{F}_s^T\mathcal{V}_s

이고 본체 좌표계에서

\mathcal{P} = \mathcal{F}_b^T\mathcal{V}_b

이며, 두 결과가 같다.

\mathcal{F}_s^T\mathcal{V}_s = \mathcal{F}_b^T\mathcal{V}_b

이 좌표 불변성은 일률이 물리적 양이므로 좌표계 선택과 무관해야 한다는 사실을 반영한다.

7. 쌍대 변환의 유도

좌표 불변성으로부터 렌치의 변환 공식을 유도할 수 있다. \mathcal{V}_s = \mathrm{Ad}_{\mathbf{T}}\mathcal{V}_b를 대입하면

\mathcal{F}_s^T\mathrm{Ad}_{\mathbf{T}}\mathcal{V}_b = \mathcal{F}_b^T\mathcal{V}_b

이 임의의 \mathcal{V}_b에 대해 성립하므로

\mathcal{F}_b^T = \mathcal{F}_s^T\mathrm{Ad}_{\mathbf{T}}

또는 전치를 취해

\mathcal{F}_b = \mathrm{Ad}_{\mathbf{T}}^T\mathcal{F}_s

이 된다. 이 관계가 렌치의 좌표 변환 공식이다.

8. 렌치 변환의 명시적 형태

공역의 전치는 다음의 명시적 형태를 가진다.

\mathrm{Ad}_{\mathbf{T}}^T = \begin{bmatrix}\mathbf{R}^T & -\mathbf{R}^T[\mathbf{t}]_\times \\ \mathbf{0} & \mathbf{R}^T\end{bmatrix}

이 행렬을 렌치에 적용하면 모멘트와 힘이 좌표 변환된다.

8.1 힘의 변환

\mathbf{f}_b = \mathbf{R}^T\mathbf{f}_s. 단순한 회전 변환이다.

8.2 모멘트의 변환

\mathbf{m}_b = \mathbf{R}^T(\mathbf{m}_s - \mathbf{t} \times \mathbf{f}_s). 모멘트의 변환은 회전뿐만 아니라 좌표 원점의 이동 효과도 포함한다. 모멘트의 기준점을 한 점에서 다른 점으로 이동할 때 발생하는 추가 항이다.

9. 렌치의 응용

9.1 매니퓰레이터 정역학

매니퓰레이터의 말단 장치에 작용하는 렌치를 알고 있을 때, 이를 지지하기 위한 관절 토크는 자코비안의 전치를 사용하여 계산된다.

\boldsymbol{\tau} = \mathbf{J}^T(\boldsymbol{\theta})\mathcal{F}

이 식은 트위스트-렌치 쌍대성의 직접적 결과이다. 자코비안이 관절 속도를 트위스트로 매핑하면, 그 전치가 렌치를 관절 토크로 매핑한다.

9.2 물체 그립과 접촉력

물체를 그립할 때 그리퍼의 접촉점에서 작용하는 힘과 모멘트가 렌치이다. 안정적 그립을 위해서는 모든 접촉점의 렌치가 합쳐져 적절한 합성 렌치를 만들어야 한다.

9.3 임피던스 제어

매니퓰레이터의 임피던스 제어에서 외부 힘과 매니퓰레이터의 가상 임피던스(질량, 감쇠, 강성)의 관계가 렌치-트위스트 관계로 표현된다.

9.4 동역학

매니퓰레이터의 동역학 방정식에서 외부 힘과 관절 토크가 렌치 형태로 표현된다. Featherstone의 articulated body algorithm은 트위스트와 렌치의 쌍대성을 활용하여 효율적인 동역학 알고리즘을 구현한다.

9.5 환경과의 상호 작용

로봇이 환경에 힘을 가하거나 환경으로부터 힘을 받는 상황(예: 압력 조절, 물체 조작, 표면 추적)에서 모든 상호 작용이 렌치로 표현된다.

10. 렌치의 분해

렌치는 다음과 같이 분해될 수 있다.

10.1 순수 힘 (모멘트가 0)

\mathcal{F}_{\text{force}} = \begin{bmatrix}\mathbf{0} \\ \mathbf{f}\end{bmatrix}

원점을 통과하는 힘선(line of action)을 따라 가해지는 단순한 힘이다.

10.2 순수 모멘트 (힘이 0)

\mathcal{F}_{\text{couple}} = \begin{bmatrix}\mathbf{m} \\ \mathbf{0}\end{bmatrix}

순수한 회전 토크이며, 위치에 무관하다(쌍힘 또는 우력, couple).

10.3 일반적 렌치

힘과 모멘트가 모두 있는 경우이다. 슈아세의 정리의 쌍대 형태에 의해, 모든 렌치는 적절한 직선 주위의 “스크류 렌치”(축을 따라 작용하는 힘과 그 축 주위의 토크)로 분해될 수 있다.

11. 렌치-스크류 분해

렌치도 스크류 형태로 분해될 수 있다.

11.1 스크류 축

렌치의 작용 직선을 결정한다. 힘 부분이 0이 아닌 경우, 스크류 축은 다음과 같다.

\hat{\mathbf{s}} = \frac{\mathbf{f}}{\lVert \mathbf{f} \rVert}, \quad \mathbf{q} = \frac{\mathbf{f} \times \mathbf{m}}{\lVert \mathbf{f} \rVert^2}

11.2 피치

렌치 피치는 다음과 같이 계산된다.

h = \frac{\mathbf{f}^T\mathbf{m}}{\lVert \mathbf{f} \rVert^2}

이는 트위스트의 피치 공식과 형태가 같으며, 이는 트위스트와 렌치의 쌍대성의 표현이다.

12. 트위스트와 렌치의 비교 표

특성트위스트렌치
차원66
첫 번째 부분각속도 \boldsymbol{\omega}모멘트 \mathbf{m}
두 번째 부분선형 속도 \mathbf{v}\mathbf{f}
좌표계 변환\mathrm{Ad}_{\mathbf{T}}\mathrm{Ad}_{\mathbf{T}}^T
무한소 형태강체 운동의 미분강체에 작용하는 일반화 힘
역할운동학적 양동역학적 양
매니퓰레이터에서자코비안 출력자코비안 전치의 입력

13. 쌍대성의 일반적 의미

트위스트와 렌치의 쌍대 관계는 운동학과 동역학 사이의 깊은 대응을 반영한다.

  • 운동(트위스트)과 힘(렌치)이 쌍대이다
  • 자코비안과 자코비안 전치가 쌍대이다
  • 일률은 두 양의 내적으로 정의되며 좌표 불변이다

이러한 쌍대성은 라그랑지언 동역학(Lagrangian dynamics), 변분 원리(variational principles), 해밀톤 동역학(Hamiltonian dynamics) 등의 고전 역학과 자연스럽게 연결된다.

14. 참고 문헌

  • 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.
  • Featherstone, R. (2008). Rigid Body Dynamics Algorithms. Springer.
  • Selig, J. M. (2005). Geometric Fundamentals of Robotics (2nd ed.). Springer.
  • Ball, R. S. (1900). A Treatise on the Theory of Screws. Cambridge University Press.

version: 1.0