쇼핑몰 자동화 시스템 프로젝트에서 Pinky 로봇 3대를 Nav2로 자율주행 제어하던 중, 특정 구간에서 반복적으로 로봇이 목표 지점에 도달하지 못하는 문제를 만났다.
증상은 크게 세 가지였다.
실제로 문제가 발생한 구간은 p3 → p4, p4 → p6, p6 → p8 로, 쇼핑몰 좁은 통로 구간이다. 로봇이 목표 지점 1m 전에서 멈추거나, 진입조차 시도하지 않았다.
Costmap inflation 문제
Nav2는 장애물 주변에 inflation layer를 적용해 로봇이 안전하게 우회할 수 있도록 한다. 문제는 좁은 통로에서 양쪽 벽의 inflation 영역이 겹쳐버리면, 해당 공간 자체가 '진입 불가'로 판단된다는 것이다. inflation_radius를 낮추면 통로를 지나갈 수 있지만, 장애물에 너무 가까이 붙어 충돌 위험이 높아진다.
AMCL 위치 추정 오차 누적
긴 경로를 이동하는 동안 AMCL 파티클 필터의 오차가 누적되면, 로봇이 자신의 위치를 잘못 인식해 goal_tolerance 기준 자체가 흔들린다.
여러 방법을 검토했다.
핵심 아이디어는 단순하다. 원거리는 Nav2가 잘하는 일(경로 계획, 장애물 회피)을 맡기고, 목표 지점 근처의 짧은 구간에서만 Nav2를 취소하고 PID 제어로 전환해 정밀하게 도달하는 것이다.
모든 구간에 동일한 PID Zone 거리를 적용하지 않았다. 구간마다 통로 너비, 장애물 분포, 필요 정밀도가 다르기 때문이다.
| 출발 POI | 도착 POI | PID 전환 거리 |
|---|---|---|
| p3 | p4 | 1.03m |
| p4 | p6 | 0.52m |
| p6 | p8 | 0.70m |
# 구간별 PID 전환 거리 설정
# (출발 POI, 도착 POI) → PID 전환 거리(m)
PID_EDGES = {
('p3', 'p4'): 1.03,
('p4', 'p6'): 0.52,
('p6', 'p8'): 0.70,
}
넓은 구간은 radius=0으로 설정해 Nav2만 사용한다.
100ms 주기로 현재 위치와 목표 지점 사이의 거리를 체크한다. 거리가 pid_zone_radius 이하로 진입하는 순간 Nav2를 취소하고 PID 모드로 전환한다.

선속도(전진)와 각속도(회전)를 별도의 PID로 제어한다.
# Linear PID (전진 제어)
Kp=0.5, Ki=0.0, Kd=0.1
max_vel = 0.15 m/s
# Angular PID (회전 제어)
Kp=1.5, Ki=0.0, Kd=0.2
max_vel = 1.0 rad/s
PID 게인은 처음에 잘 설계된 초기값에서 시작해, 실제 주행 테스트에서 오버슈트가 발생하지 않도록 max_vel만 낮추는 방향으로 조정했다.
한 가지 포인트: 각도 오차가 30° 이상이면 전진 속도를 0으로 설정하고 제자리 회전을 먼저 수행한다. 방향이 크게 틀어진 상태에서 전진하면 목표에서 더 멀어지는 경우가 생기기 때문이다. (요건 April tag로 yaw 재정렬하는 방식으로 각도오차를 줄이도록 개선할 예정이다)
_zone_check(): Nav2 → PID 전환 판단
def _zone_check(self):
dx = self.goal_x - self.current_x
dy = self.goal_y - self.current_y
dist = math.sqrt(dx**2 + dy**2)
key = (self.start_poi, self.goal_poi)
radius = PID_EDGES.get(key, 0.0)
if radius > 0 and dist < radius:
self._switch_to_pid()
_pid_loop(): PID 제어 루프 (50Hz)
def _pid_loop(self):
dx = self.goal_x - self.current_x
dy = self.goal_y - self.current_y
dist = math.sqrt(dx**2 + dy**2)
if dist < 0.05:
self._complete()
return
angle_to_goal = math.atan2(dy, dx)
angle_err = angle_to_goal - self.current_yaw
# 각도 정규화 (-pi ~ pi)
angle_err = math.atan2(math.sin(angle_err), math.cos(angle_err))
angular_vel = self.angular_pid.compute(angle_err)
# 각도 오차 30도 이상이면 전진 정지
if abs(angle_err) > math.radians(30):
linear_vel = 0.0
else:
linear_vel = self.linear_pid.compute(dist)
self._publish_cmd(linear_vel, angular_vel)
goal_generation 번호로 이전 콜백 무시 (race condition 방지)map → base_footprint) 조회 실패 시 해당 주기 스킵| 구간 | Nav2만 사용 | Nav2 + PID |
|---|---|---|
| p4 → p6 | 목표 0.8m 전에서 정지 | 목표 도달 (오차 < 5cm) |
| p6 → p8 | 좁은 구간 진입 포기 | 정상 도달 |
p4 → p6 구간은 Nav2만 사용했을 때 항상 0.8m 전에서 멈췄는데, PID 전환 후에는 오차 5cm 이내로 도달하게 됐다. p6 → p8은 아예 진입을 포기하던 구간이었는데 정상 도달이 가능해졌다.
Nav2는 강력한 프레임워크지만, 좁은 공간에서의 정밀 도달에는 구조적 한계가 있다. inflation을 낮추는 것만으로는 충돌 안전성을 희생해야 하고, goal_tolerance를 높이면 정밀도가 떨어진다.
이번에 구현한 Nav2 + PID 하이브리드 방식은 두 가지를 모두 포기하지 않는 실용적인 해법이었다. '원거리는 Nav2, 근거리는 PID'라는 단순한 원칙이 생각보다 잘 동작했다.
ROS2로 실제 로봇을 제어하면서 교과서적인 파라미터 튜닝만으로 해결되지 않는 문제들이 있다는 걸 느꼈다. 그럴 때는 시스템의 한계를 인정하고, 다른 제어 방식을 조합하는 접근이 유효한 것 같다.