6.103 특이점 근방에서의 댐핑 기법
1. 개요
로봇 매니퓰레이터의 역기구학 해법에서 야코비안 행렬이 랭크를 잃는 특이 배치(singular configuration)는 핵심적인 기술 과제이다. 특이점에서는 의사 역행렬을 통한 관절 속도가 무한대로 발산하며, 특이점 근방에서도 비현실적으로 큰 관절 속도가 발생한다. 이 절에서는 특이점의 수학적 특성을 분석하고, 댐핑 기법을 통해 이를 안정적으로 처리하는 다양한 방법을 다룬다.
2. 특이점의 수학적 정의
야코비안 \mathbf{J}(\boldsymbol{\theta}) \in \mathbb{R}^{m \times n}에 대해, 특이 배치란 \text{rank}(\mathbf{J}(\boldsymbol{\theta})) < \min(m, n)인 관절 각도 \boldsymbol{\theta}를 말한다.
특이값 분해 \mathbf{J} = \mathbf{U} \boldsymbol{\Sigma} \mathbf{V}^\top에서 특이점은 하나 이상의 특이값이 0이 되는 배치이다. 특이점 근방에서는 최소 특이값 \sigma_{\min}이 매우 작아진다.
2.1 특이점의 분류
| 분류 | 설명 | 물리적 의미 |
|---|---|---|
| 경계 특이점 (Boundary singularity) | 작업 공간의 경계에서 발생 | 팔이 완전히 펴지거나 접힌 상태 |
| 내부 특이점 (Internal singularity) | 작업 공간 내부에서 발생 | 두 관절 축이 정렬되는 상태 |
3. 의사 역행렬의 발산 문제
의사 역행렬을 SVD로 표현하면
\mathbf{J}^+ = \sum_{i=1}^{r} \frac{1}{\sigma_i} \mathbf{v}_i \mathbf{u}_i^\top
이다. 특이점 근방에서 \sigma_r \to 0이면 1/\sigma_r \to \infty가 되어, 역기구학 해
\dot{\boldsymbol{\theta}} = \mathbf{J}^+ \dot{\mathbf{x}}_d = \sum_{i=1}^{r} \frac{\mathbf{u}_i^\top \dot{\mathbf{x}}_d}{\sigma_i} \mathbf{v}_i
에서 \sigma_r에 대응하는 방향의 관절 속도 성분이 발산한다.
3.1 조건수에 의한 특성화
야코비안의 조건수(condition number)는
\kappa(\mathbf{J}) = \frac{\sigma_{\max}}{\sigma_{\min}}
로 정의된다. 특이점 근방에서 \kappa(\mathbf{J}) \to \infty가 되어 역문제의 수치적 조건이 악화된다.
4. 기본 댐핑 최소 제곱법 (DLS)
4.1 정식화
Wampler(1986)와 Nakamura-Hanafusa(1986)가 독립적으로 제안한 댐핑 최소 제곱법은 다음 정규화된 최적화 문제를 푼다.
\min_{\dot{\boldsymbol{\theta}}} \left( \| \mathbf{J} \dot{\boldsymbol{\theta}} - \dot{\mathbf{x}}_d \|_2^2 + \lambda^2 \| \dot{\boldsymbol{\theta}} \|_2^2 \right)
해는 다음과 같다.
\dot{\boldsymbol{\theta}} = \mathbf{J}^\top (\mathbf{J} \mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1} \dot{\mathbf{x}}_d
SVD를 이용하면
\dot{\boldsymbol{\theta}} = \sum_{i=1}^{r} \frac{\sigma_i}{\sigma_i^2 + \lambda^2} (\mathbf{u}_i^\top \dot{\mathbf{x}}_d) \mathbf{v}_i
필터 계수 \sigma_i / (\sigma_i^2 + \lambda^2)는 \sigma_i가 아무리 작아져도 유계(bounded)이다. 구체적으로
\frac{\sigma_i}{\sigma_i^2 + \lambda^2} \leq \frac{1}{2\lambda}
이 항상 성립한다. 등호는 \sigma_i = \lambda일 때 달성된다.
5. 적응적 댐핑 기법
5.1 고정 댐핑의 한계
고정 댐핑 파라미터 \lambda를 사용하면 특이점에서 멀리 떨어진 일반 배치에서도 불필요한 태스크 오차가 발생한다. 따라서 야코비안의 상태에 따라 \lambda를 동적으로 조절하는 적응적 댐핑이 필요하다.
5.2 Nakamura-Hanafusa 방식
최소 특이값 \sigma_{\min}을 기준으로 댐핑 파라미터를 설정한다.
\lambda^2 = \begin{cases} 0 & \text{if } \sigma_{\min} \geq \epsilon \\ \lambda_{\max}^2 \left(1 - \left(\dfrac{\sigma_{\min}}{\epsilon}\right)^2\right) & \text{if } \sigma_{\min} < \epsilon \end{cases}
여기서 \epsilon은 특이점 감지 임계값, \lambda_{\max}는 최대 댐핑 값이다. 이 방식은 특이점에서 멀리 떨어지면 댐핑이 0이 되어 정확한 추종을 보장하고, 특이점에 가까워지면 댐핑이 증가하여 안정성을 확보한다.
5.3 조작도 기반 방식
Yoshikawa(1985)의 조작도(manipulability) 지표
w = \sqrt{\det(\mathbf{J} \mathbf{J}^\top)} = \prod_{i=1}^{m} \sigma_i
를 이용하여 댐핑 파라미터를 설정한다.
\lambda^2 = \begin{cases} 0 & \text{if } w \geq w_{\min} \\ \lambda_{\max}^2 \left(1 - \left(\dfrac{w}{w_{\min}}\right)^2\right) & \text{if } w < w_{\min} \end{cases}
이 방식은 전체 특이값의 곱에 기반하므로 전반적인 특이점 근접도를 반영한다.
5.4 조건수 기반 방식
조건수 \kappa = \sigma_{\max} / \sigma_{\min}을 기준으로 한다.
\lambda^2 = \begin{cases} 0 & \text{if } \kappa \leq \kappa_{\max} \\ \lambda_{\max}^2 \left(1 - \left(\dfrac{\kappa_{\max}}{\kappa}\right)^2\right) & \text{if } \kappa > \kappa_{\max} \end{cases}
6. 선택적 댐핑 (Selective Damping)
6.1 방향별 댐핑
Maciejewski와 Klein(1988)은 모든 방향에 동일한 댐핑을 적용하는 대신, 특이값이 작은 방향에만 선택적으로 댐핑을 적용하는 방법을 제안하였다. 이를 SVD 기반으로 표현하면
\dot{\boldsymbol{\theta}} = \sum_{i=1}^{r} \frac{\sigma_i}{\sigma_i^2 + \lambda_i^2} (\mathbf{u}_i^\top \dot{\mathbf{x}}_d) \mathbf{v}_i
여기서 각 방향에 대한 댐핑 파라미터를 개별적으로 설정한다.
\lambda_i^2 = \begin{cases} 0 & \text{if } \sigma_i \geq \epsilon \\ \lambda_{\max}^2 \left(1 - \left(\dfrac{\sigma_i}{\epsilon}\right)^2\right) & \text{if } \sigma_i < \epsilon \end{cases}
6.2 행렬 형태
선택적 댐핑을 행렬로 표현하면
\dot{\boldsymbol{\theta}} = \mathbf{J}^\top (\mathbf{J} \mathbf{J}^\top + \boldsymbol{\Lambda})^{-1} \dot{\mathbf{x}}_d
여기서 \boldsymbol{\Lambda} = \mathbf{U} \text{diag}(\lambda_1^2, \lambda_2^2, \dots, \lambda_m^2) \mathbf{U}^\top이다. 이 방법은 크게 영향받는 방향에만 댐핑을 적용하므로, 일반 방향에서는 추종 정확도를 유지할 수 있다.
7. 연속성 보장
7.1 불연속 댐핑의 문제
임계값 기반의 댐핑 전환에서 \lambda가 불연속적으로 변화하면, 관절 속도에 갑작스러운 변화(jerk)가 발생할 수 있다. 이는 로봇의 기계적 구조에 부담을 주며 제어 성능을 저하시킨다.
7.2 연속 전환 함수
시그모이드 함수 등 부드러운 전환 함수를 사용하여 댐핑을 연속적으로 변화시킨다.
\lambda^2(\sigma_{\min}) = \frac{\lambda_{\max}^2}{1 + \exp\left(\dfrac{\sigma_{\min} - \epsilon}{\delta}\right)}
여기서 \delta > 0은 전환의 급격함을 제어하는 파라미터이다. \delta가 작을수록 더 급격한 전환이 이루어진다.
8. 태스크 공간 오차 분석
댐핑을 도입하면 태스크 공간에서 추종 오차가 발생한다. 이 오차를 정량적으로 분석한다.
댐핑 역기구학 해 \dot{\boldsymbol{\theta}}_{\text{DLS}} = \mathbf{J}^\top (\mathbf{J}\mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1} \dot{\mathbf{x}}_d에 대해, 실현되는 태스크 속도는
\dot{\mathbf{x}}_{\text{actual}} = \mathbf{J} \dot{\boldsymbol{\theta}}_{\text{DLS}} = \mathbf{J}\mathbf{J}^\top (\mathbf{J}\mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1} \dot{\mathbf{x}}_d
SVD로 표현하면
\dot{\mathbf{x}}_{\text{actual}} = \sum_{i=1}^{r} \frac{\sigma_i^2}{\sigma_i^2 + \lambda^2} (\mathbf{u}_i^\top \dot{\mathbf{x}}_d) \mathbf{u}_i
따라서 태스크 오차는
\dot{\mathbf{x}}_d - \dot{\mathbf{x}}_{\text{actual}} = \sum_{i=1}^{r} \frac{\lambda^2}{\sigma_i^2 + \lambda^2} (\mathbf{u}_i^\top \dot{\mathbf{x}}_d) \mathbf{u}_i
\sigma_i \gg \lambda인 방향에서는 오차 계수 \lambda^2 / (\sigma_i^2 + \lambda^2) \approx 0이므로 오차가 거의 없고, \sigma_i \ll \lambda인 방향에서는 오차 계수가 1에 근접하여 해당 방향의 추종이 포기된다.
9. 관절 속도 상한과의 관계
댐핑 파라미터 \lambda를 관절 속도 상한 \dot{\theta}_{\max}와 연관시킬 수 있다. 관절 속도의 상한이
\| \dot{\boldsymbol{\theta}} \|_2 \leq \dot{\theta}_{\max}
로 주어질 때, 댐핑 역기구학에서의 관절 속도 상한은
\| \dot{\boldsymbol{\theta}}_{\text{DLS}} \| \leq \frac{\| \dot{\mathbf{x}}_d \|}{2\lambda}
이므로, \lambda \geq \| \dot{\mathbf{x}}_d \| / (2 \dot{\theta}_{\max})로 설정하면 관절 속도 제한을 보장할 수 있다.
10. 알고리즘 요약
적응적 댐핑 역기구학 알고리즘:
- 현재 관절 각도 \boldsymbol{\theta}_k에서 야코비안 \mathbf{J}(\boldsymbol{\theta}_k)를 계산한다.
- \mathbf{J}의 SVD를 수행하여 특이값 \sigma_1 \geq \sigma_2 \geq \cdots \geq \sigma_r를 구한다.
- \sigma_{\min}에 따라 댐핑 파라미터 \lambda(또는 방향별 \lambda_i)를 계산한다.
- 관절 속도를 계산한다.
\dot{\boldsymbol{\theta}} = \sum_{i=1}^{r} \frac{\sigma_i}{\sigma_i^2 + \lambda_i^2} (\mathbf{u}_i^\top \dot{\mathbf{x}}_d) \mathbf{v}_i
- 관절 각도를 갱신한다: \boldsymbol{\theta}_{k+1} = \boldsymbol{\theta}_k + \dot{\boldsymbol{\theta}} \Delta t
- 수렴 여부를 판단하고, 미달이면 1단계로 돌아간다.
11. 참고 문헌
- Nakamura, Y., & Hanafusa, H. (1986). “Inverse Kinematic Solutions with Singularity Robustness for Robot Manipulator Control.” Journal of Dynamic Systems, Measurement, and Control, 108(3), 163–171.
- Wampler, C. W. (1986). “Manipulator Inverse Kinematic Solutions Based on Vector Formulations and Damped Least-Squares Methods.” IEEE Transactions on Systems, Man, and Cybernetics, 16(1), 93–101.
- Maciejewski, A. A., & Klein, C. A. (1988). “Numerical Filtering for the Operation of Robotic Manipulators through Kinematically Singular Configurations.” Journal of Robotic Systems, 5(6), 527–552.
- Yoshikawa, T. (1985). “Manipulability of Robotic Mechanisms.” The International Journal of Robotics Research, 4(2), 3–9.
- Buss, S. R. (2004). “Introduction to Inverse Kinematics with Jacobian Transpose, Pseudoinverse and Damped Least Squares methods.” Department of Mathematics, University of California, San Diego.
- Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
v 0.1