32.41 감쇠 최소 제곱(Damped Least Squares) 역자코비안
감쇠 최소 제곱 역자코비안은 Tikhonov 정칙화를 자코비안 기반 역기구학에 적용한 수치 기법으로, 특이 근방에서 표준 의사 역행렬의 노름 발산을 정칙화 항으로 완화하면서 정확도와 안정성 사이의 절충을 매개 변수 \lambda로 명시적으로 조정한다. Nakamura와 Hanafusa가 1986년 논문 “Inverse kinematic solutions with singularity robustness for robot manipulator control“에서, 그리고 Wampler가 같은 해 논문 “Manipulator inverse kinematic solutions based on vector formulations and damped least-squares methods“에서 독립적으로 제안한 이 기법은, 매니퓰레이터 자코비안 처리에서 가장 널리 사용되는 정칙화 도구로 자리잡았다. 본 절에서는 감쇠 최소 제곱 역자코비안의 정의와 최적화 해석을 정리한 뒤, 특이값 필터링 표현, 감쇠 인자의 선택 기법, 성능 절충, 그리고 가중·선택적 변형으로의 확장을 차분하게 기술한다.
1. 정의와 정칙화 최소 제곱 해석
자코비안 \mathbf{J}(\vec{q}) \in \mathbb{R}^{m \times n}과 작업 공간 속도 명령 \dot{\vec{x}} \in \mathbb{R}^m이 주어졌을 때, 감쇠 최소 제곱 해는 다음 정칙화 최소 제곱 문제의 해로 정의된다. \dot{\vec{q}}^\ast = \arg\min_{\dot{\vec{q}}}\, \bigl( \lVert \mathbf{J}(\vec{q})\,\dot{\vec{q}} - \dot{\vec{x}} \rVert_2^2 + \lambda^2\,\lVert \dot{\vec{q}} \rVert_2^2 \bigr). 여기서 \lambda > 0은 정칙화 강도를 결정하는 감쇠 인자이며, 두 항은 각각 잔여 노름 최소화와 해의 노름 최소화를 조합한다. 정규 방정식 (\mathbf{J}^\top \mathbf{J} + \lambda^2 \mathbf{I})\,\dot{\vec{q}} = \mathbf{J}^\top\,\dot{\vec{x}}로부터 명시적 해 \dot{\vec{q}}^\ast = (\mathbf{J}^\top \mathbf{J} + \lambda^2 \mathbf{I})^{-1}\,\mathbf{J}^\top\,\dot{\vec{x}}가 얻어지며, 행렬 항등식을 이용하면 \dot{\vec{q}}^\ast = \mathbf{J}^\top (\mathbf{J} \mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1}\,\dot{\vec{x}}의 대등한 형태로도 표현된다. 이로부터 감쇠 최소 제곱 역자코비안은 \mathbf{J}^\sharp = \mathbf{J}^\top (\mathbf{J} \mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1}로 정의된다.
이 정의의 형식은 표준 의사 역행렬 \mathbf{J}^+ = \mathbf{J}^\top (\mathbf{J} \mathbf{J}^\top)^{-1}의 역행렬 항에 정칙화 항 \lambda^2 \mathbf{I}를 더한 단순한 변형으로 보이지만, 그 효과는 본질적이다. \lambda \to 0인 극한에서 \mathbf{J}^\sharp \to \mathbf{J}^+로 환원되어 표준 의사 역행렬과 동일해지며, \lambda가 증가함에 따라 차단 방향에 평행한 명령 성분의 응답이 감쇠된다. 또한 \mathbf{J} \mathbf{J}^\top이 특이 근방에서 양정 부족 상태에 빠지는 표준 의사 역행렬과 달리, 정칙화 항의 추가는 \mathbf{J} \mathbf{J}^\top + \lambda^2 \mathbf{I}를 항상 양정으로 유지하므로 역행렬이 모든 관절 구성에서 잘 정의된다. 이는 감쇠 최소 제곱 역자코비안이 자코비안의 계수와 무관하게 항상 산출 가능한 연산자임을 의미한다.
2. 특이값 필터링 표현과 응답 함수
감쇠 최소 제곱 역자코비안의 본질적 거동은 자코비안의 특이값 분해 \mathbf{J} = \mathbf{U}\,\boldsymbol{\Sigma}\,\mathbf{V}^\top를 통해 명료하게 드러난다. 정의를 특이값 분해에 대입하여 정리하면 \mathbf{J}^\sharp = \mathbf{V}\,\boldsymbol{\Sigma}^\sharp\,\mathbf{U}^\top의 형태가 되며, 여기서 \boldsymbol{\Sigma}^\sharp의 대각 원소는 각 특이값에 대응하는 응답 \sigma_i / (\sigma_i^2 + \lambda^2)로 주어진다. 이 응답 함수는 \sigma_i \gg \lambda인 정상 모드에서는 1/\sigma_i에 근접하여 표준 의사 역행렬과 사실상 동일하게 작용하고, \sigma_i \ll \lambda인 차단 모드에서는 \sigma_i/\lambda^2로 영에 수렴한다. 응답의 최댓값은 \sigma_i = \lambda에서 1/(2\lambda)가 되며, 이 값은 감쇠 최소 제곱 역자코비안의 노름 상한 \lVert \mathbf{J}^\sharp \rVert_2 \le 1/(2\lambda)를 결정한다.
이 응답 함수의 형태는 감쇠 최소 제곱 역자코비안의 핵심 성질을 한 식으로 요약한다. 첫째, 관절 속도의 노름이 \lambda의 역수에 비례하여 명시적으로 상한이 부여되므로, 액추에이터 속도 한계와 토크 한계의 명시적 관리가 가능해진다. 둘째, 정상 모드의 응답이 1/\sigma_i에 근접하므로 자코비안이 정상 상태에 있는 영역에서는 표준 의사 역행렬과 사실상 구별되지 않는 정밀도가 유지된다. 셋째, 차단 모드의 응답이 영으로 매끄럽게 감쇠하므로, 표준 의사 역행렬에서 발생하는 무한 발산이 해소되며 시스템의 폐루프 안정성이 보장된다. 그 대가로 차단 방향의 작업 공간 명령은 더 이상 정확히 추종되지 않으며, 이로부터 잔여 추적 오차가 발생한다. 이 절충 관계는 감쇠 최소 제곱 역자코비안의 본질적 특성으로, 매개 변수 \lambda의 선택을 통해 운영자가 명시적으로 관리한다.
3. 감쇠 인자의 선택과 적응 전략
감쇠 인자 \lambda의 선택은 정확도와 안정성 사이의 균형을 결정하므로, 일정한 매개 변수가 모든 작업과 모든 매니퓰레이터 구성에 적합한 것은 아니다. 정상 영역에서는 \lambda가 작아야 정확도가 보존되며, 특이 근방에서는 \lambda가 충분히 커야 노름 발산이 억제된다. 이를 동시에 달성하기 위한 표준적 접근은 자코비안의 최소 특이값 또는 매니퓰러빌리티 측도에 따라 \lambda를 적응적으로 조정하는 가변 감쇠 전략이다. Wampler가 1986년 논문에서 제시한 형태는 임계 임곗값 \epsilon을 도입하여 \sigma_{\min} \ge \epsilon이면 \lambda = 0, \sigma_{\min} < \epsilon이면 \lambda^2 = \lambda_0^2 (1 - (\sigma_{\min}/\epsilon)^2)로 설정하는 단조 가변 형태이다. 이 형태는 특이 근방의 가장자리에서 매끄럽게 정칙화 강도를 증가시키므로 제어 신호의 불연속 변동을 발생시키지 않는다.
자코비안 행렬식의 절댓값을 직접 활용하는 형태로 \lambda^2 = \lambda_0^2 \exp(-w(\vec{q})/w_0)와 같은 비선형 가중 함수도 흔히 사용되며, 매니퓰러빌리티 측도가 영으로 접근할수록 정칙화가 강화된다. 이러한 적응 전략은 정상 영역에서의 정밀도와 특이 근방에서의 안정성을 동시에 확보하는 표준적 방안으로 자리잡았다. Maciejewski와 Klein이 1988년 논문 “Numerical filtering for the operation of robotic manipulators through kinematically singular configurations“에서 제안한 수치 필터링은 이러한 적응적 정칙화의 일반화이며, 모드별로 서로 다른 감쇠를 적용하는 다음 절의 선택적 감쇠 최소 제곱법으로 자연스럽게 발전한다. 매개 변수의 결정은 매니퓰레이터의 부동 소수점 정밀도, 액추에이터의 속도·토크 한계, 작업의 정밀도 요구, 샘플링 주기를 종합적으로 고려하여 이루어지며, 일반적으로 시뮬레이션과 시범 운전을 통해 보정된다.
4. 폐루프 안정성과 추적 오차의 정량화
감쇠 최소 제곱 역자코비안을 분해 운동 속도 제어에 적용한 폐루프 시스템은 표준 의사 역행렬 기반 제어와 본질적으로 다른 거동을 보인다. 작업 공간 추적 오차 \vec{e} = \vec{x}_d - \vec{f}(\vec{q})에 대하여 폐루프 동역학은 \dot{\vec{e}} = \dot{\vec{x}}_d - \mathbf{J}\,\mathbf{J}^\sharp\,(\dot{\vec{x}}_d + \mathbf{K}\,\vec{e})의 형태로 정리되며, 여기서 \mathbf{K}는 양정 이득 행렬이다. 정상 영역에서는 \mathbf{J}\,\mathbf{J}^\sharp \approx \mathbf{I}이므로 추적 오차가 지수적으로 감쇠하지만, 특이 근방에서는 \mathbf{J}\,\mathbf{J}^\sharp가 단위 행렬에서 멀어져 \sigma_i^2/(\sigma_i^2 + \lambda^2)의 응답을 가지는 사영 연산자로 변형된다. 그 결과 차단 방향에 대한 추적 오차는 영으로 수렴하지 않고 일정한 잔류 오차를 형성한다.
이 잔류 오차의 크기는 감쇠 인자 \lambda와 명령 신호의 차단 방향 성분의 크기에 의해 정량적으로 결정되며, 차단 방향 명령 성분 \dot{x}_n에 대한 잔류 추적 오차는 시간이 충분히 경과한 후 \lambda^2/(\sigma_{\min}^2 + \lambda^2)\,\dot{x}_n / k의 차수를 가진다. 따라서 감쇠 최소 제곱 역자코비안의 사용은 차단 방향에 대한 정확한 추적을 의도적으로 포기하고 그 대가로 시스템의 안정성과 액추에이터 한계의 보장을 얻는 절충에 해당한다. 이 절충은 작업의 특성에 따라 적절성이 달라진다. 자세 추종이 부차적인 위치 조립 작업에서는 손목 특이점의 잔류 자세 오차가 허용 가능한 반면, 정밀 자세 정렬이 요구되는 광학 정렬 작업에서는 잔류 오차가 그대로 작업 실패로 이어질 수 있다. 따라서 감쇠 최소 제곱법은 단독으로 사용되기보다 작업 우선순위 처리, 명령 변형, 여유 자유도 활용 등 다른 전략과 결합되는 경우가 일반적이다.
5. 확장 변형과 본 절의 정리
감쇠 최소 제곱 역자코비안은 다양한 확장 형태로 일반화된다. 가중 감쇠 최소 제곱 역자코비안 \mathbf{J}^\sharp_{\mathbf{W}_q,\lambda} = \mathbf{W}_q^{-1}\,\mathbf{J}^\top (\mathbf{J}\,\mathbf{W}_q^{-1}\,\mathbf{J}^\top + \lambda^2 \mathbf{I})^{-1}은 가중 의사 역행렬과 정칙화의 결합으로, 관절 한계 회피, 동적 일관성, 단위 정규화와 결합하여 사용된다. 작업 공간 가중 감쇠 형태 \mathbf{J}^\sharp_{\mathbf{W}_x,\lambda} = (\mathbf{J}^\top \mathbf{W}_x \mathbf{J} + \lambda^2 \mathbf{I})^{-1}\,\mathbf{J}^\top \mathbf{W}_x는 작업 공간 방향별 정밀도 가중을 결합한다. 또한 후속 절에서 다루어질 선택적 감쇠 최소 제곱법은 자코비안의 특이값 분해를 직접 활용하여 모드별로 서로 다른 감쇠 인자를 적용하며, 정상 모드의 정밀도를 더욱 보존하면서 차단 모드만 강하게 감쇠하는 효율적 변형을 제공한다. 우선순위 기반 다중 작업 처리에서는 각 작업의 자코비안에 감쇠 최소 제곱 정칙화를 단계적으로 적용하여 작업 사이의 상충과 특이 근방의 안정성을 동시에 다룬다.
본 절에서 다룬 감쇠 최소 제곱 역자코비안은 Tikhonov 정칙화를 자코비안 사상에 도입하여 표준 의사 역행렬의 노름 발산을 차단하면서 정상 영역의 정밀도를 보존하는 표준 도구이다. 정의는 정칙화 최소 제곱 문제의 명시적 해로 단일하게 정리되며, 특이값 응답 함수 \sigma/(\sigma^2 + \lambda^2)는 감쇠 거동의 모든 본질을 한 식으로 요약한다. 감쇠 인자의 적응적 선택은 정상 영역의 정밀도와 특이 근방의 안정성을 동시에 확보하는 핵심이며, 잔류 추적 오차의 정량화와 폐루프 안정성의 보장은 이 기법의 사용 절충을 명확히 한다. 가중 변형, 작업 공간 가중, 선택적 감쇠, 우선순위 결합 등 다양한 확장은 감쇠 최소 제곱법이 매니퓰레이터 자코비안 처리의 통합적 수치 도구로 기능함을 보여 주며, 본 절은 후속 절에서 다루어질 선택적 감쇠와 자코비안 전치 기법으로 이어지는 출발점을 제공한다.
6. 출처
- Tikhonov, A. N., “On the stability of inverse problems”, Doklady Akademii Nauk SSSR, Vol. 39, No. 5, pp. 195–198, 1943.
- Nakamura, Y. and Hanafusa, H., “Inverse kinematic solutions with singularity robustness for robot manipulator control”, ASME Journal of Dynamic Systems, Measurement, and Control, Vol. 108, No. 3, pp. 163–171, 1986.
- Wampler, C. W., “Manipulator inverse kinematic solutions based on vector formulations and damped least-squares methods”, IEEE Transactions on Systems, Man, and Cybernetics, Vol. 16, No. 1, pp. 93–101, 1986.
- Maciejewski, A. A. and Klein, C. A., “Numerical filtering for the operation of robotic manipulators through kinematically singular configurations”, Journal of Robotic Systems, Vol. 5, No. 6, pp. 527–552, 1988.
- Chiaverini, S., Egeland, O., and Kanestrom, R. K., “Achieving user-defined accuracy with damped least-squares inverse kinematics”, in Proceedings of the IEEE International Conference on Advanced Robotics, pp. 672–677, 1991.
- Buss, S. R., “Introduction to inverse kinematics with Jacobian transpose, pseudoinverse and damped least squares methods”, Technical Report, University of California San Diego, 2009.
- Sciavicco, L. and Siciliano, B., Modelling and Control of Robot Manipulators, 2nd edition, Springer, 2000.
7. 버전
- 문서 버전: 2.0
- 작성일: 2026-04-26