6.12 제어 모듈의 성능 평가 지표
자율주행 제어 모듈의 성능을 체계적으로 평가하기 위해서는 정량적 지표(quantitative metric)의 정의와 측정 방법론이 필수적이다. 성능 평가 지표는 제어기의 설계 목표를 수치적으로 검증하고, 서로 다른 제어 기법 간의 비교를 가능하게 하며, 시스템의 안전성과 승차감 수준을 객관적으로 판단하는 기준을 제공한다. 본 절에서는 자율주행 제어 모듈에서 사용되는 주요 성능 평가 지표를 범주별로 분류하고, 각 지표의 수학적 정의, 물리적 의미, 그리고 일반적인 허용 기준을 기술한다.
1. 경로 추종 정확도 지표
경로 추종 정확도는 차량이 참조 경로를 얼마나 정확하게 따라가는지를 나타내는 지표로, 횡방향 제어의 성능을 직접적으로 반영한다.
1.1 횡방향 위치 오차(Lateral Position Error)
횡방향 위치 오차 e_{lat}(t)는 차량의 기준점과 참조 경로 사이의 수직 거리이다. 이 오차에 대한 통계적 지표는 다음과 같이 정의된다.
평균 절대 오차(Mean Absolute Error, MAE):
\text{MAE}_{lat} = \frac{1}{T} \int_0^T \lvert e_{lat}(t) \rvert \, dt
이산 시간 형태에서는 다음과 같다.
\text{MAE}_{lat} = \frac{1}{N} \sum_{k=1}^{N} \lvert e_{lat}[k] \rvert
제곱 평균 제곱근 오차(Root Mean Square Error, RMSE):
\text{RMSE}_{lat} = \sqrt{\frac{1}{T} \int_0^T e_{lat}^2(t) \, dt}
최대 절대 오차(Maximum Absolute Error):
e_{lat,\max} = \max_{t \in [0,T]} \lvert e_{lat}(t) \rvert
각 지표의 일반적인 허용 기준은 다음과 같다.
| 지표 | 고속도로 주행 | 도심 주행 | 주차 |
|---|---|---|---|
| \text{MAE}_{lat} | < 0.10 m | < 0.15 m | < 0.05 m |
| \text{RMSE}_{lat} | < 0.15 m | < 0.20 m | < 0.08 m |
| e_{lat,\max} | < 0.30 m | < 0.50 m | < 0.15 m |
1.2 방향각 오차(Heading Error)
방향각 오차 e_\psi(t) = \psi(t) - \psi^{ref}(t)는 차량의 실제 방향과 참조 경로의 접선 방향 간의 각도 차이이다. 방향각 오차의 MAE와 RMSE는 횡방향 위치 오차와 동일한 형태로 산출된다.
\text{RMSE}_\psi = \sqrt{\frac{1}{N} \sum_{k=1}^{N} e_\psi^2[k]}
일반적으로 \text{RMSE}_\psi < 2° (약 0.035 rad)가 양호한 횡방향 제어의 기준으로 간주된다.
2. 속도 추종 정확도 지표
속도 추종 정확도는 종방향 제어의 성능을 나타내며, 목표 속도 프로파일에 대한 실제 속도의 일치 정도를 평가한다.
2.1 속도 오차(Speed Error)
e_v(t) = v^{ref}(t) - v_x(t)
\text{RMSE}_v = \sqrt{\frac{1}{N} \sum_{k=1}^{N} e_v^2[k]}
일반적인 허용 기준은 \text{RMSE}_v < 1.0 m/s이다.
2.2 정지 위치 정확도(Stop Position Accuracy)
정지 제어에서의 성능은 목표 정지 위치와 실제 정지 위치 간의 편차로 평가된다.
e_{stop} = s_{actual} - s_{target}
양의 값은 과진행(overshoot), 음의 값은 미달(undershoot)을 의미한다. 일반적으로 \lvert e_{stop} \rvert < 0.3 m이 요구되며, 정밀 주차에서는 \lvert e_{stop} \rvert < 0.1 m이 요구된다.
3. 승차감 지표(Ride Comfort Metrics)
승차감은 자율주행 차량의 사용자 수용도(user acceptance)를 결정하는 중요한 요소이다. 승차감 관련 지표는 차량에 작용하는 가속도와 그 변화율에 기반하여 정의된다.
3.1 종방향 가속도(Longitudinal Acceleration)
종방향 가속도 a_x(t)의 크기는 승객이 느끼는 전후 방향의 관성력에 대응한다.
| 가속도 범위 | 승차감 수준 |
|---|---|
| \lvert a_x \rvert < 1.5 m/s^2 | 쾌적(comfortable) |
| 1.5 \leq \lvert a_x \rvert < 3.0 m/s^2 | 감지 가능(noticeable) |
| \lvert a_x \rvert \geq 3.0 m/s^2 | 불쾌(uncomfortable) |
3.2 횡방향 가속도(Lateral Acceleration)
횡방향 가속도 a_y(t)는 선회 시 승객이 느끼는 원심력에 대응한다.
a_y \approx v_x^2 \kappa = \frac{v_x^2}{R}
일반적으로 \lvert a_y \rvert < 2.0 m/s^2가 쾌적한 선회의 기준이며, \lvert a_y \rvert > 4.0 m/s^2는 불쾌감을 유발한다.
3.3 저크(Jerk)
저크는 가속도의 시간 미분으로, 가속도 변화의 급격함을 나타낸다. 종방향 저크 j_x와 횡방향 저크 j_y는 다음과 같이 정의된다.
j_x(t) = \frac{da_x(t)}{dt}, \quad j_y(t) = \frac{da_y(t)}{dt}
저크의 허용 기준은 다음과 같다.
| 지표 | 쾌적 기준 | 허용 한계 |
|---|---|---|
| 종방향 저크 \lvert j_x \rvert | < 1.0 m/s^3 | < 2.5 m/s^3 |
| 횡방향 저크 \lvert j_y \rvert | < 0.5 m/s^3 | < 1.5 m/s^3 |
ISO 2631-1(1997) 표준에 따르면, 전신 진동(whole-body vibration)에 대한 승차감 평가는 가속도의 주파수 가중 실효값(frequency-weighted RMS)을 기반으로 수행된다.
4. 제어 입력 평활도 지표(Control Smoothness Metrics)
제어 입력의 평활도는 구동기의 수명, 에너지 효율, 그리고 승차감에 영향을 미친다.
4.1 조향각 변화율(Steering Rate)
\dot{\delta}_{rms} = \sqrt{\frac{1}{N} \sum_{k=1}^{N} \left(\frac{\delta[k] - \delta[k-1]}{T_s}\right)^2}
조향각 변화율의 RMS 값이 클수록 조향 명령이 불안정하며, 승객에게 불쾌감을 줄 수 있다.
4.2 가속도 변화율(Acceleration Rate)
\dot{a}_{x,rms} = \sqrt{\frac{1}{N} \sum_{k=1}^{N} \left(\frac{a_x[k] - a_x[k-1]}{T_s}\right)^2}
4.3 제어 입력의 총 변동(Total Variation)
제어 입력의 총 변동(Total Variation, TV)은 제어 입력의 누적 변화량을 나타낸다.
\text{TV}_\delta = \sum_{k=1}^{N} \lvert \delta[k] - \delta[k-1] \rvert
\text{TV}_{a_x} = \sum_{k=1}^{N} \lvert a_x[k] - a_x[k-1] \rvert
총 변동이 작을수록 제어 입력이 부드러우며, 구동기의 마모를 줄이고 에너지 효율을 향상시킨다.
5. 안전성 지표(Safety Metrics)
5.1 차선 이탈 빈도(Lane Departure Rate)
차량의 횡방향 위치가 차선 경계를 초과하는 횟수 또는 시간 비율이다.
R_{LD} = \frac{T_{departure}}{T_{total}} \times 100 \; [\%]
여기서 T_{departure}는 차선 이탈 누적 시간, T_{total}은 전체 주행 시간이다. 자율주행 시스템에서는 R_{LD} = 0\%가 목표이다.
5.2 안전 한계 침범 빈도(Safety Boundary Violation Rate)
조향각, 가속도, 요레이트 등의 제어 변수가 사전에 정의된 안전 한계를 침범하는 빈도이다.
R_{SV} = \frac{N_{violation}}{N_{total}} \times 100 \; [\%]
5.3 TTC(Time to Collision)
TTC는 현재 속도와 상대 속도를 유지할 때 선행 차량 또는 장애물과 충돌하기까지의 예상 시간이다.
\text{TTC} = \frac{d}{v_{rel}}
여기서 d는 차간 거리, v_{rel}은 상대 속도이다. 일반적으로 \text{TTC} > 3 s가 안전한 종방향 제어의 기준으로 사용된다.
6. 실시간 성능 지표(Real-time Performance Metrics)
6.1 제어 연산 시간(Control Computation Time)
제어 알고리즘이 한 주기의 제어 입력을 산출하는 데 소요되는 시간이다. 이 시간은 제어 주기보다 짧아야 한다.
t_{comp} < T_s
MPC와 같이 최적화 문제를 풀어야 하는 제어기에서는 연산 시간이 중요한 성능 지표가 된다. 연산 시간의 평균값뿐만 아니라 최악 경우(worst-case) 연산 시간도 보고되어야 한다.
6.2 제어 주기 지터(Control Cycle Jitter)
실제 제어 주기와 설계 주기 사이의 편차이다. 주기 지터가 크면 제어 성능이 저하되고 안정성 문제가 발생할 수 있다.
\sigma_{jitter} = \sqrt{\frac{1}{N} \sum_{k=1}^{N} (T_s[k] - \bar{T}_s)^2}
7. 통합 성능 평가
개별 지표를 종합하여 제어 모듈의 전반적인 성능을 평가하기 위하여, 가중 합산(weighted sum) 방식의 통합 성능 지수(overall performance index)가 사용되기도 한다.
J_{overall} = w_1 \cdot \text{RMSE}_{lat} + w_2 \cdot \text{RMSE}_v + w_3 \cdot j_{x,rms} + w_4 \cdot j_{y,rms} + w_5 \cdot \dot{\delta}_{rms}
가중치 w_i는 적용 시나리오에 따라 조정된다. 예를 들어, 고속도로 주행에서는 경로 추종 정확도와 안정성에 높은 가중치를 부여하고, 도심 저속 주행에서는 승차감에 높은 가중치를 부여한다.
8. 평가 시나리오
제어 모듈의 성능 평가는 다양한 주행 시나리오에서 수행되어야 포괄적인 검증이 가능하다. 대표적인 평가 시나리오는 다음과 같다.
| 시나리오 | 평가 항목 | 주요 지표 |
|---|---|---|
| 직선 차선 유지 | 횡방향 추종 정확도, 안정성 | \text{RMSE}_{lat}, e_{lat,\max} |
| 곡선 구간 주행 | 곡선 추종 성능, 횡방향 가속도 | \text{MAE}_{lat}, a_{y,\max} |
| 차선 변경 | 과도 응답, 승차감 | e_{lat,\max}, j_{y,\max} |
| 속도 변화 구간 | 속도 추종 정확도, 저크 | \text{RMSE}_v, j_{x,\max} |
| 정지 및 출발 | 정지 위치 정확도, 출발 평활도 | e_{stop}, j_{x,rms} |
| 비상 상황 | 최대 감속도, 응답 시간 | a_{x,\max}, t_{response} |
참고문헌
- ISO. (1997). ISO 2631-1: Mechanical Vibration and Shock — Evaluation of Human Exposure to Whole-Body Vibration. International Organization for Standardization.
- Bae, I., Moon, J., & Seo, J. (2020). Toward a Comfortable Driving Experience for a Self-Driving Shuttle Bus. Electronics, 9(6), 943.
- Paden, B., Čáp, M., Yong, S. Z., Yershov, D., & Frazzoli, E. (2016). A Survey of Motion Planning and Control Techniques Adopted in Self-Driving Vehicles. IEEE Transactions on Intelligent Vehicles, 1(1), 33–55.
- Rajamani, R. (2012). Vehicle Dynamics and Control (2nd ed.). Springer.
버전: 2026-04-11 v1.0