본문으로 건너뛰기

제어 튜닝

언제 이 가이드가 필요한가?

기본 PID 게인은 Indy7에 최적화되어 있습니다. 다음 경우에만 튜닝이 필요합니다:

  • 무거운 페이로드 장착 시 (진동 또는 추적 오차 증가)
  • 새 로봇 모델 추가 시 (기본 게인이 없을 때)
  • 높은 정밀도가 필요할 때 (RMS 추적 오차 < 0.001 rad)

기본값으로 시작하고, 문제가 발생할 때만 아래 내용을 참조하세요.


제어 모드

PLEM은 상태 머신이 관리하는 여러 제어 모드를 지원합니다:

모드추적중력 보상마찰 보상PID사용 사례
TRAJECTORYOOOO정상 동작, 경로 실행
FREEDRIVEXOXX수동 티치, 사용자가 로봇 안내
BRAKEDN/AN/AN/AN/A토크 0, 서보가 브레이크로 위치 유지
P_STOP (보호)XOXX안전 정지, 한계 초과

FREEDRIVE에서 마찰 보상이 비활성화되는 이유: 사용자가 로봇을 직접 안내할 때 target_velocity ≈ actual_velocity가 되어 양의 피드백 루프(폭주)가 발생하기 때문입니다.


토크 제어 개요

JointTorqueController는 다음 동역학 방정식을 구현합니다:

τ=G(q)+C(q,q˙)q˙+M(q)q¨+F(q˙)+τPID\tau = G(q) + C(q, \dot{q})\dot{q} + M(q)\ddot{q} + F(\dot{q}) + \tau_{PID}
구성 요소역할활성화 시기
중력 G(q)무게 상쇄 (KDL 기반)항상
코리올리 C(q,q̇)q̇속도 의존 힘 상쇄항상
관성 M(q)q̈가속도 피드포워드target_accelerations 제공 시
마찰 F(q̇)관절 마찰 보상TRAJECTORY 모드 전용
PID τ_PID추적 피드백TRAJECTORY 모드 전용

핵심 API:

#include <plem/control/joint_torque_controller.hpp>

// calculate_joint_torque()의 disable_tracking 파라미터:
// false → 전체 제어 (TRAJECTORY)
// true → 중력+코리올리 보상만 (FREEDRIVE, P_STOP)
auto torque = controller.calculate_joint_torque(
joint_angles, joint_velocities,
target_positions, target_velocities, target_accelerations,
/*disable_tracking=*/false);

PID 게인 설정

PID 파라미터 구조

struct PIDParameter {
double kp; // 비례 게인 [Nm/rad]
double ki; // 적분 게인 [Nm/(rad·s)]
double kd; // 미분 게인 [Nm/(rad/s)]
double max_integral; // 안티 와인드업 한계
double max_output; // 출력 포화 [Nm]
};

기본 게인 (Indy7)

관절KpKiKdmax_integralmax_output비고
J0 (베이스)81001042050200높은 관성, 강한 강성
J1 (어깨)81001042050200최대 중력 토크
J2 (엘보우)21001012050200중간 관성
J3 (손목1)21001012050200낮은 관성
J4 (손목2)21001012050200낮은 관성
J5 (손목3)21001012050200최소 마찰

설계 근거: 중력 보상이 정적 부하 대부분을 처리하므로 Ki가 작습니다 (10). 베이스/어깨는 높은 관성 때문에 강한 Kp (8100)와 높은 댐핑 Kd (420)가 필요합니다.

사용자 정의 게인 적용

#include <plem/control/joint_torque_controller.hpp>
#include <plem/control/defaults/indy7.hpp>

// 기본값에서 시작하여 수정
auto custom_gains = indy7::PIDGains;

// 무거운 페이로드(5kg)를 위한 어깨 강성 증가
custom_gains[1].kp = 10000.0; // 8100 → 10000
custom_gains[1].kd = 500.0; // 420 → 500
custom_gains[1].max_output = 250.0;

// 페이로드 없는 손목은 공격성 감소
custom_gains[5].kp = 1500.0; // 2100 → 1500

PIDController<6> pid(custom_gains);

파라미터 효과 요약

파라미터너무 낮으면너무 높으면일반적 범위
Kp느린 응답, 큰 오차진동, 오버슈트1000-10000
Ki정상 상태 바이어스와인드업, 느린 진동5-20
Kd오버슈트, 링잉노이즈 증폭, 채터링100-500
max_integral포화 시 느린 회복와인드업 허용50-200
max_outputPID 응답 제한하드웨어 손상 위험50-250

마찰 보상 파라미터

PLEM은 부드러운 쿨롱 마찰 모델을 사용합니다:

τfriction=Fctanh(ω0.05)\tau_{friction} = F_c \cdot \tanh\left(\frac{\omega}{0.05}\right)

tanh는 영속도 근처에서 부드러운 전환을 제공하여 채터링을 방지합니다 (sign() 대비).

기본 마찰 계수 (Indy7)

관절Fc [Nm]비고
J0 (베이스)6.5큰 베어링, 낮은 마찰
J1 (어깨)36.68하중 지지, 최고 마찰
J2 (엘보우)9.0중간
J3 (손목1)2.2낮은 질량
J4 (손목2)2.6낮은 질량
J5 (손목3)1.0최소 마찰

마찰 계수 식별 방법

  1. 로봇을 중력 보상 모드로 설정 (또는 수평 장착)
  2. 각 관절에 일정 속도 명령 (0.5 rad/s)
  3. 정상 상태 모션 중 평균 토크 측정
  4. Fc = average_torque (고속에서 tanh ≈ 1)

튜닝 워크플로우

권장 순서

  1. Kp만 튜닝 (Ki=0, Kd=0): 0.1 rad 스텝 입력으로 오버슈트 < 10%까지 증가
  2. Kd 추가: Kp/20에서 시작, 오버슈트 소멸까지 증가
  3. Ki 추가: 0.1에서 시작, 잔여 오차 < 0.001 rad까지 증가
  4. 안티 와인드업 설정: max_integral = 5 * (typical_error / Ki)
  5. 출력 한계 설정: max_output = 0.8 * max_joint_torque

관절별 가이드라인

관절 그룹Kp 범위Kd 범위특성
베이스/어깨 (J0-J1)6000-10000300-500높은 관성, 높은 Kd 허용
엘보우 (J2)2000-3000100-200특이점 근처 주의
손목 (J3-J5)1000-250080-150마찰 지배적, 공격적 튜닝 가능

모니터링 도구

# 실시간 관절 상태 모니터링
ros2 topic echo /joint_states

# PlotJuggler로 시각화 (추적 오차, 토크 등)
ros2 run plotjuggler plotjuggler
# ROS2 Subscriber → /joint_states, /rt_raw 토픽 추가

# RT 루프 성능 확인
ros2 topic echo /rt_raw --field loop_jitter_us
ros2 topic echo /rt_raw --field loop_exec_us

좋은 응답 기준

메트릭허용우수
오버슈트< 10%< 5%
정착 시간 (0.1 rad 스텝)< 0.5s< 0.2s
정상 상태 오차< 0.005 rad< 0.002 rad
RMS 추적 오차 (모션 중)< 0.005 rad< 0.002 rad

성능 참고

W-RC 측정치 (Indy7, PREEMPT_RT):

메트릭측정값비고
전체 루프 실행 시간60-80 µsKDL 동역학 포함
루프 지터12-42 µsclock_nanosleep TIMER_ABSTIME
중력 보상18-25 µs전체의 ~30%
코리올리 보상20-28 µs전체의 ~35%
마찰 + PID3-5 µs전체의 ~5%

1kHz 제어 주기 (1000 µs) 대비 충분한 여유가 있습니다.


다음 단계