Journal of Korea Robotics Society
[ ARTICLE ]
Journal of Korea Robotics Society - Vol. 15, No. 2, pp.147-159
ISSN: 1975-6291 (Print) 2287-3961 (Online)
Print publication date May 2020
Received 18 Nov 2019 Revised 30 Jan 2020 Accepted 3 Feb 2020
DOI: https://doi.org/10.7746/jkros.2020.15.2.147

자율 주차 시스템을 위한 주차 경로 추종 방법의 비교 연구

김민성1 ; 임규범2 ; 박재흥
A Comparative Study of Parking Path Following Methods for Autonomous Parking System
Minsung Kim1 ; Gyubeom Im2 ; Jaeheung Park
1PhD student, Graduate School of Convergence Science and Technology, Seoul National University, Seoul, Korea minsungkim@snu.ac.kr
2MS student, Graduate School of Convergence Science and Technology, Seoul National University, Seoul, Korea edwardim@snu.ac.kr

Correspondence to: Professor, Corresponding author: Graduate School of Convergence Science and Technology. Seoul National University, Seoul, Korea. Advanced Institutes of Convergence Science and Technology. park73@snu.ac.kr)

© Korea Robotics Society. All rights reserved.

Abstract

Over the last years, a number of different path following methods for the autonomous parking system have been proposed for tracking planned paths. However, it is difficult to find a study comparing path following methods for a short path length with large curvature such as a parking path. In this paper, we conduct a comparative study of the path following methods for perpendicular parking. By using Monte-Carlo simulation, we determine the optimal parameters of each controller and analyze the performance of the path following. In addition, we consider the path following error occurred at the switching point where forward and reverse paths are switched. To address this error, we conduct the comparative study of the path following methods with the one thousand switching points generated by the Monte-Carlo method. The performance of each controller is analyzed using the V-rep simulator. With the simulation results, this paper provides a deep discussion about the effectiveness and limitations of each algorithm.

Keywords:

Path Following, Motion Control, Model Predictive Control, Intelligent Vehicle, Autonomous Parking System

1. 서 론

최근에 자율 주행 기술들이 활발히 개발되면서 고속도로뿐 만 아니라 도심에서도 사용 가능한 자율 주행 기술들이 개발 되고 있다[1]. 대표적인 도심 도로에서의 자율 주행 기술 연구 로 주차 보조 시스템 연구가 있고, 자기 위치 인식 기술이나 주 차 공간 인식 등과 같은 기술과 통합된 완전 자율 주차 시스템 연구로 확장되고 있다[2]. 자율 주차 시스템 연구는 특정 제한 조건에서만 최적으로 주차가 가능한 한계를 가진 기존의 상용 주차 보조 시스템과 다르게 어떠한 초기(Initial) 위치에서도 주차 경로를 생성하여 주차하는 것을 목표로 하고 있다.

자율 주차는 주차 공간 주변 환경을 인지(Recognition)하는 파트와 주행 가능한 주차 경로 생성(Path Planning) 및 경로 추 종(Path Following) 파트로 구성된다. 인식된 주차 공간을 바탕 으로 주행 가능한 주차 경로가 생성되면, 주변 차량 및 장애물 과의 충돌을 피하면서 정확한 위치에 주차를 해야 하기 때문 에 주차 경로는 정밀하게 추종 되어야 한다.

일반적인 전방 경로 추종 문제보다 상대적으로 주차 경로 추종 문제는 더 어렵다[3]. 그 이유로 다음과 같이 세 가지를 들 수 있다. 첫 번째, 주차 경로 추종은 경로 추종(Path Tracking/ Following) 문제이면서 동시에 차량의 자세(Posture: 위치 및 방위)를 어떤 하나의 주차 목표 자세로 수렴시키는 점-안정화 (Point Stabilization) 문제다. 이 문제는 Brockett’s necessary condition[4]에 의해 제어 입력보다 자유도가 더 큰 논홀로노믹 (Non-Holonomic) 시스템의 안정화 문제로써 시-불변(Timeinvariant) 입력 피드백 제어 법칙에 의해서는 안정화 될 수 없 다는 점에서 어려운 문제이다. 두 번째, 주차 환경에서 생성된 주차 경로는 일반 주행 경로보다 길이가 짧고 곡률이 크다. 만 일, 주차를 수행하는 로봇이 차량형(Car-like) 로봇이라면, 일 반적인 차륜형(Differential Drive) 모바일 로봇보다 큰 선회 반 경의 한계를 가지고 있으며 주차 경로는 길이가 짧기 때문에 로봇이 주차 경로 추종 오차를 빠르게 줄이지 못하면 주차가 실 패 될 수 있다. 이렇게 일반적인 자율 주행의 경로 추종 상황보 다 상대적으로 경로 길이가 짧은 주차 경로 추종의 특성을 고려 하기 위해서는 과도 응답 특성이 좋은 제어기가 필요하다[5,6]. 마지막으로, 주차 경로 추종은 자율 주행 자동차의 적응형 순 항 제어(Adaptive Cruise Control), 차선 유지 시스템(Lane Keeping System) 등과 같은 다양한 주행 기술 분야 중, 가장 정밀한 주 행 제어 성능을 요구한다.

본 논문에서는 자율 주차에 적용될 수 있는 경로 추종 방법 에 대해서 소개하고, 각 제어 방법별 정성적/정량적 분석을 수 행하였다. 특히, 위에서 언급한 곡률이 크며 경로의 길이가 짧 고 경로의 끝 점이 있는 후방 주차 경로에 대해서 경로 추종 방 법들의 성능 비교를 수행하였다. 또한, 실제 차량으로 주차 경 로를 추종하는 상황을 고려하여 제어 입력 외란에 대한 제어 기의 성능도 비교 분석하였다.

본 논문의 구성은 다음과 같다. 2장에서는 기존에 경로 추 종 방법으로 제안되었던 알고리즘들의 특징에 대해 설명을 하 고, 3장에서는 이러한 경로 추종 방법 중, 주차 경로 추종에 적 용될 수 있는 알고리즘들에 관해서 기술한다. 4장에서는 로봇 시뮬레이터인 V-rep 환경에서 각 제어 방법에 사용되는 최적 의 제어 파라미터를 찾고 이를 이용하여 제어 입력에 외란이 있을 시, 주차 경로 추종 성능을 비교한다. 그 다음, 주차 할 때 전/후진 전환 지점에서 임의의 초기 주차 경로 추종 오차에 대 한 각 제어 방법별 성능 평가 및 장/단점 분석을 하고, 5장에서 본 논문을 결론짓는다.


2. 관련 연구

경로 추종 방법으로써 대표적으로 알려진 Stanley[7], Purepursuit [8]와 같은 geometric 방법과 adaptive PID 제어기 등은 구현이 쉬우며 계산 비용이 적다는 장점이 있다. 그러나, 이 방 법들은 큰 곡률에서 불안정성을 보일 수 있으며 오차에 대해 응답을 하는 방법이기 때문에 목표 경로에 급격한 곡률이 있 을 때, 과도 응답 특성이 좋지 않다. 특히, 2005년 미국 국방 고 등기획국이 후원하여 개최한 자율 주행 자동차 대회에서[9], Stanford 팀의 경로 추종 제어기로 알려진 Stanley 방법은 후방 주차 경로 추종 시, 제어 입력 출력 관계가 비-최소 위상 시스 템(Non-Minimum Phase System)을 구성하기 때문에 후방 경 로 추종에 적합하지 않다[5]. Pure-pursuit는 휴리스틱(Heuristic) 하게 정한 look-ahead 거리에 따라 경로 추종 성능이 크게 좌 우되며 cutting corner와 같은 문제를 발생시킬 수 있다. 또한, 이 제어기는 look-ahead 거리를 이용함으로써 과도 응답 (Transient Response) 특성을 좋게 하는 장점이 있으나, 근본적 으로 주차 경로 추종 제어기로 적용하기에는 방위 오차를 고 려하지 않는 한계가 있다. 한편, Pure-pursuit와 유사하게 방법 으로, look-ahead 거리 개념을 이용하면서 동시에 차량과 가 장 가까운 목표 점과 특정 거리에 있는 목표 점에서의 오차까 지 고려하여 만든 경로 추종 알고리즘(Input-output feedback linearization with preview, 이하 Preview)도 연구 되었다[10]. 이 방법은 예견 거리(Preview Distance)에 있는 목표점에서의 거리 오차를 고려하여 과도 응답 특성이 좋다는 장점이 있다. 또한, 차륜형 모바일 로봇의 경로 추종 방법으로 사용된 Kanayama[11] 제어기는 목표 요(yaw)가 포함된 제어 방법으로 경로 추종 시, 목표 경로의 곡률을 이용한다는 점에서 과도 응답 특성이 좋 은 제어 방법이다.

Fuzzy 제어기[12]와 Sliding mode 제어기는 차량 모델에 기반 하지 않는 방법으로써 좋은 제어 성능을 보였으나[13], 퍼지 제 어 입력을 설립하기 위하여 매우 많은 실제 경험을 필요로 하며, Sliding mode 제어기는 채터링(Chattering) 문제로 인하여 승차 감 저해가 수반되고, 실제 차에 적용하기에 한계가 있다.

이에 반해, 차량 모델에 기반한 주차 경로 추종 방법으로써 대표적인 방법인 Linear Quadratic Regulator (LQR)[14] 방법 및 Model Predictive Control (MPC) 방법이 있다. LQR은 대수 리 카티 방정식(Algebraic Riccati Equation)을 풀어 제어 이득을 구하는 방법으로 제어 오차가 발생 되었을 때에만, 해당 오차 에 반응하여 제어 입력을 구하기 때문에 제어 오차를 발생시 킬 수 있다. 이에 반해, MPC는 시스템의 실제 물리적인 제약 조건을 고려하면서 동시에 비용 함수를 최소로 하는 최적의 제어 입력을 구한다는 장점이 있으며 근래에 주차 경로 추종 에 적용 되었고 제어 성능이 확인 되었다[1].

기존의 경로 추종 방법에 대한 연구 외에 다양한 경로 추종 방법을 비교한 연구들도 있었다. Brezak et al.는 세 가지 제어기 를 비교하여 가장 적은 경로 추종 오차를 보이면서 동시에 외란 에 강인한 제어기에 대한 성능 평가를 하였고[15], non-linear 제 어 방법의 성능이 가장 낫다는 결론을 지었다. Heb et al.과 Calzolari et al.에서도 차량 모델의 불확실성에 대한 제어기의 성능을 비교하였고, 제어기별 성능을 분석 할 수 있는 벤치마 크 테스트 프레임워크를 제안했으나, 주차 경로와 같이 경로 가 끝나는 목표 경로에 대한 분석이 이뤄지지 않았으며 벤치 마크 테스트를 할 수 있는 해당 사이트는 더 이상 이용할 수 없 다[16,17]. Dominguez et al.는 경로 추종 알고리즘으로 Stanley Pure-pursuit, Slide mode control, Lateral speed control 방법에 대해서 시뮬레이션과 실제 차량 테스트로 전방 경로 추종 성 능을 비교하였다[18].

기존의 경로 추종 방법들은 대부분 전방 경로 추종에서만 제어 성능을 비교했기 때문에 공통적으로 경로의 곡률이 크 고, 경로 길이가 짧은 주차 경로 추종에 바로 적용하기에는 한 계가 있다. 다음 장에서는 앞에서 언급한 것처럼 주차 경로 추 종 제어기로써의 가져야 할 특성이 고려된 세 가지 제어 방법 (Kanayama, Preview 및 MPC)들을 소개하며 알고리즘별 장단 점에 대해 논하고자 한다.


3. 주차 경로 추종 방법

3.1 Kanayama Controller

Kanayama 제어기는 1990년 Kanayama et. al. 가 제안 하였 다[11]. 이 경로 추종 제어기는 geometric 경로 추종 방법으로써, 구현이 쉽고 다른 제어기에 비해 상대적으로 계산 비용이 적다 는 장점이 있다. [Fig. 1]에서 보면, 로봇은 현재 자세(xc, yc, ψc) 에서 세 가지 자유도(Degree of Freedom)를 지니고 있고 xr, yrψr은 기준 자세다. 제어 입력은 다음과 같이 계산된다. 우 선, 식 (1)에서 보면, 관성 좌표계에 대한 기준 궤적과 현재 모 바일 로봇의 위치 및 자세의 차이는 모바일 로봇 기준 좌표계 대해 표현될 수 있다. 모바일 로봇의 위치 및 방위 오차는 모바 일 로봇의 기준 좌표계에 대해서 정의된다(xe, ye, ψe). 이렇게 정의된 오차 자세(Pe)를 시간에 대해 미분하고, 이동 로봇의 논홀노믹 구속 조건(x˙csinθcy˙ccosθc=0)을 대입한 뒤, 리 아푸노프(Lyapunov) 함수를 구성하여 정리하면 식 (2)가 얻어 지며 자세한 수식 유도 과정은 해당 논문을 참고한다[11].

[Fig. 1]

Kanayama error posture: error posture with respect to the Kanayama controller

Pe=[xeyeψe]=[cos(ψc)sin(ψc)0sin(ψc)cos(ψc)0001]([xryrψr][xcycψc])=[cos(ψc)(xrxc)+sin(ψc)(yryr)sin(ψc)(xrxc)+cos(ψc)(yryc)ψrψc](1) 

υc=υrcos(ψe)+Kxxe,ωc=ωr+υr(Kyye+Kesin(ψe))(2) 

Kanayama et al. 논문에서 υcωc는 각각 선 속도와 각속도 제어 입력이며 υrωr는 목표 선 속도와 목표 각속도를 의미 한다. Kx, Ky,Ke는 양수 상수인 제어 파라미터다. 이 제어 파 라미터를 사용하여 Kanayama 제어기는 일정한 곡률을 가진 경로 추종에 대한 안정성을 보장 할 수 있다[11]. Kanayama 제 어기는 모바일 로봇의 현재 선속도와 각속도가 요구되는 속 도와 완벽히 일치한다는 가정하에 제안되었으며 전통적으 로 차륜형 모바일 로봇의 궤적 추종 제어에 사용되어 왔다. Kanayama 제어기를 차량과 같은 로봇에 적용하기 위해서 위 에서 언급한 제어 입력 중 각속도는 바로 제어 입력으로 적용 되지 않으며 해당 각속도를 생성하기 위한 조향각(δ)이 제어 입력으로 사용 되어야 한다. 여기에서 사용되는 모델은 3.3절 에서 설명 되어 있다. 이러한 차륜형 모바일 로봇과 차량과 같 은 형태의 로봇의 기구학적 유사성으로 인하여 Kanayama 제 어기는 식 (3)과 같은 관계를 가질 수 있다. 최종 제어 입력 δ는 다음과 같이 구해진다.

ωc=κυ=tanδLυ,δ=tan1ωcLυ(3) 

κ는 순간 선회 반경(Instantaneous Radius of Turn)의 역수로 곡률(Curvature)을 의미한다. L은 차량의 축간 길이(Wheel base)를 의미한다.

앞서 언급된 주차 경로 추종용 제어기의 특징으로써 Kanayama 제어기에서는 목표 yaw rate (ωr ) 부분이 있다. 식 (2)에서 보 면, ωr 부분은 횡 방향의 거리 오차와 방위 오차를 고려한 부 분이 더해져 있다. 이러한 형태가 경로 추종 중 가장 가까운 목표점을 추종하다가 발생한 오차를 줄여주는 feedback 제어 기 역할을 하고, 이미 주어진 목표 경로를 고려한 feed-forward 형태의 역할을 하는 제어기로 구성된다. 즉, 경로 추종 오차가 없을 때에는 경로와 매우 가까운 곳에 차량이 놓인 상황이며 이때, 목표 경로로부터 곡률을 기반으로 한 조향각을 계산할 수 있다. 결과적으로 feed-forward 부분은 주차 경로 추종 시, 과도 응답 특성을 좋게 만드는 역할을 한다.

3.2 Input-output feedback linearization with preview controller (Preview controller)

Preview 제어기는 후방 경로 추종을 하기 위해 Rajamani et al.에 의해 개발되었다[10]. 이 제어기는 차량으로 곡률이 있는 경로를 추종 할 때, 차량 뒷바퀴 중심에서 일정한 예견 거리에 있는 목표점을 설정하고 이 목표점에서 정의한 횡 방향 거리 오차를 줄인다는 점이 특징이다. 우선, 차량 뒷바퀴에서 예견 거리(l)만큼 떨어진 점에 가상의 바퀴가 있다고 가정하고, 가 상의 바퀴에서 목표 경로에 수직으로 내린 목표 경로 점 (Waypoint)을 예견 위치(Preview Point)라고 정의한다[Fig. 2]. 가상의 바퀴에서부터 예견 위치까지의 거리를 횡 방향 거리 오차 s라고 정의한다. yb는 차량 뒷바퀴에서 목표 경로와 가장 가까운 점이고, 이 경로 점의 방위 정보가 목표 방위 ψd이며, s를 이용해서 구한 예견 위치에서의 목표 방위는 ψpd이다. s는 배각 공식과 α=ψdψpd2 관계 및 small angle theorem에 의 해 다음과 같이 식 (4)로 계산된다.

[Fig. 2]

Geometry relationship of the preview controller

s=yd+l(e2+ψd+ψpd2)(4) 

여기서 e2은 뒷바퀴에서 목표 경로와 가장 가까운 점과의 방 위 오차이다. s˙=λs 로 놓으면 다음 식 (5)와 같은 관계를 얻 을 수 있다. λ는 양수인 제어 파라미터이다.

y˙b+l(e˙2+ψ˙dψ˙pd2)=λs(5) 

e2 = ψ - ψd로 놓고 이를 미분한 뒤, ψ=υLtanδ 관계 를 고려하여 식 (5)에 넣으면 제어 입력인 식 (6)으로 정리할 수 있으며 υ는 차량의 속력이고 L은 차량의 축간 길이다.

δ=Llυtan1(λybλle2λlψdψpd2-y˙b+(ψ˙d+ψ˙pd)l2)(6) 

제어기의 자세한 유도는 해당 논문을 참고한다[10]. Preview 제어기는 주차 경로 추종 제어기로써 예견 거리에 위치해 있 는 목표점에 대한 오차를 정의하고 이를 줄이는 제어 입력을 구하기 때문에 과도 응답 특성이 개선된다[5]. 이 제어기는 임 의의 예견 거리를 사용한다는 점에서 대표적인 geometric 제 어기인 Pure-pursuit 방법과 유사하다. 그러나, Preview 제어기 는 예건 거리에 있는 점에서의 방위 오차로 생긴 횡 방향 거리 오차를 줄이기 때문에 방위 오차는 상관없이 목표점에 선회 운동으로 도달할 수 있는 조향각을 구하는 Pure-pursuit보다 더 나은 제어 성능을 기대할 수 있다.

3.3 Model Predictive Controller

MPC를 이용하여 경로 추종 할 때, 주차 공간에서의 차량은 저속으로 이동하기 때문에 차량 기구학 모델을 이용하여 차량 의 움직임은 표현될 수 있다. 본 연구에서는 효율적인 계산을 위해서 선형 MPC를 구현 하였다. MPC에 사용된 모델은 비선 형 차량 기구학 모델이다[Fig. 3]. [Fig. 3]은 차량의 전/후 두 바 퀴가 각각 하나의 바퀴로 표현되는 모델이며 xc, yc는 각각 차 량의 뒷바퀴 중심의 위치를 의미한다. xr(i),yr(i) 에서 r은 목 표 위치 점을 의미하며, r(i)는 i번째 목표 위치 점을 의미한 다. 기구학 모델은 식 (7)로 정리될 수 있다.

[Fig. 3]

Kinematic bicycle model for the MPC

x˙=υcos(ψ),y˙=υsin(ψ),ψ˙=υtan(δ)L(7) 

위와 같은 비선형 모델은 Talyor 확장을 이용한 선형화 (Linearization)를 통해 선형 MPC에 적용될 수 있다. Talyor 확 장은 비선형 차량 모델과 평형 상태(Equilibrium state)를 의미 하는 목표 경로 점과 관계를 통해 정의되는데, 이는 차량 모델과 선 형화하고자 하는 목표 모델(Xr=[xr,yr,ψr]T,Ur=[υr,δr]T)과 의 차이 형태로 정의되며 x˜=XXru˜=UUr 로 표현될 수 있다 (X=[x,y,ψ]T,U=[υ,δ]T). 이와 같이 선형화 된 식을 이 산화(Discretization)하면 다음과 같은 식으로 나타낼 수 있다.

x˜(k+1)=A(k)x˜(k)+B(k)u˜(k)(8) 

식 (8)은 선형 시변(Linear Time-Varying) 시스템을 의미하 고, A(k)와 B(k) 행렬은 다음과 같다.

A(k)=[10υr,ksin(ψr,k)T01υr,kcos(ψr,k)T001]B(k)=[cos(ψr,k)T0sin(ψr,k)T0tan(δr,k)TLυr,k(1+tan2(δr,k))TL](9) 

L은 차량의 축간 길이를 의미한다. υr,kψr,k는 각각 k 순 간의 목표 속력과 목표 경로 위치의 목표 방위 값이며 T는 샘 플링 주기, δr,k는 목표 조향각이다. 여기서 δr,k는 차량이 목표 경로점 위에 놓였을 때, 다음 목표점으로 경로 추종하는데 필 요한 조향각을 의미한다.

주차 경로 추종은 2장에서 언급된 바와 같이 일반적인 고속 도로 경로 추종에 비해 과도 응답 특성이 더 요구되기 때문에 경로의 예견 정보가 필요하다. MPC 방법은 차량 모델을 이용 하여 차량의 미래 거동을 예측하고 미리 정의해 놓은 비용 함 수를 최소화하는 최적 제어 입력을 구하는 방식이기 때문에 경로 추종 시, 경로의 예견 정보가 이용됨을 알 수 있다. 비용 함수는 다음과 같다.

minu˜(k)J(k)=i=1Hp1x˜(k+i)TQx˜(k+i)+x˜(k+Hp)TPx˜(k+Hp)+i=0Hc1u˜(k+i)TRu˜(k+i)s.t.x˜0=x˜(k),x˜(k+i+1)=A(k+i)x˜(k+i)+B(k+j)u˜(k+j)u˜minu˜(k+j)u˜max(10) 

위에서 x˜0 는 현재 k에서의 시스템 상태 값이다. ij의 범 위는 각각 i[0,Hp1],j[0,Hc1] 이며 Hp는 예측 구간, Hc는 제어 구간이고 동일하게 설정하였다. Q는 시스템 상태 의 가중 매트릭스이고 P는 종단(Terminal) 시스템 상태에 대한 가중 매트릭스이며 QP는 동일하게 설정하였다. R은 제어 입력 상태 가중 매트릭스이다. 입력 제약 조건인 u˜min,u˜max 에 는 최대 조향각(±540°)을 이용하였다. MPC는 위의 비용 함수 를 최소화하는 제어 입력 벡터를 구하고 이 중 첫 번째 값을 최 종 제어 입력으로 이용한다. 이를 위해 식(10)은 QP (Quadratic Programming)에 대입하기 위한 식으로 변환한 뒤 이를 최소화 하는 제어 입력을 구한다. 본 연구에서는 MPC의 최적화 계산 을 위한 solver로써 CVXGEN의 QP를 이용하였다[19]. 제어 주 기는 10Hz로 적용하였다. 최종 제어 입력은 최적화를 통해 얻 은 최적 제어 입력 벡터인 u˜k*(k[0,Hc1]) 의 첫 번째 조향 값과 앞에서 구한 목표 조향각 (δr,k)값의 첫 번째 값을 더해서 구한다.

이러한 MPC 기반 경로 추종 방법은 차량의 모델을 이용하 여 차량의 미래 거동과 목표 경로와의 오차를 최소화하면서 동시에, 조향각 범위나 조향 각속도 범위와 같은 물리적인 제 약(Constraints)을 고려할 수 있다는 장점이 있다. 그러나, 본 연구에서는 효율적인 제어 입력 계산을 위해 선형 MPC를 수 행하였고, 이를 위해 목표점에 대해서 선형화를 수행한 모델 을 사용한다는 점에서 목표점과 멀리 떨어져 있는 상태에서는 선형화 모델의 기본 가정에 위배될 수 있는 한계가 있다. 다음 장 에서는 세 가지 주차 경로 추종 방법의 성능 비교를 수행하였다.


4. 실험 및 결과

4.1 실험 환경 및 제어기 파라미터 결정 방법

본 연구는 세 가지 경로 추종 알고리즘을 이용한 경로 추종 성능을 테스트하기 위해서 ROS (Robot Operating System) 기 반의 V-rep 시뮬레이터를 사용하였다[20]. 차량 모델은 V-rep에 서 제공하는 Simple Ackermann Steering 모델을 사용하였고, 기구학 정보는 현대자동차 그랜져 HG240의 제원을 이용하였 다. 시뮬레이션을 수행한 컴퓨터 사양은 Intel i7 4.2GHz, 16 GB RAM이다. 시뮬레이션의 주차장은 경기도 수원시 영통구 에 위치한 차세대융합기술연구원 주차장 환경을 실제 측정하 여 제작되었다[Fig. 4].

[Fig. 4]

V-rep simulator environment

한편, 주차 경로는 대표적인 샘플링 기반 경로 생성 알고리 즘인 RRT (Rapidly-exploring Random Trees) star를 사용하였 고[21], 차량의 구속 조건을 고려하였으며 경로 계획 라이브러리 인 Open Motion Planning Library (OMPL)를 이용하여 구현 되 었다[22]. 주차 시, 차량의 거동은 저속이기 때문에 Ackermann 조향으로 차량의 순간 선회 반경을 계산할 수 있다. RRT star 로 생성된 경로의 최대 곡률은 0.07이며, 이는 Ackermann 조향 에 따라, 축간 거리 2.978 m인 차량에서 최대 조향이 30°일 때 최대 곡률이 0.2077(1/선회 반경) 이기 때문에 차량이 추종할 수 있는 경로이다. 경로는 여러 개의 경로 점들로 구성되어 있 으며 실제 주차 환경에서는 매 순간 목표 경로 대비 자차의 상 대 위치를 정확하게 알기 어렵지만, 시뮬레이션에서는 이를 정확하게 알고 있다고 가정하였다.

제어기는 일반적으로 제어 입력 계산에 관여하는 파라미터 에 따라 제어 성능이 바뀐다. 본 절에서는 미리 정의된 비용 함 수를 최소화하는 제어 이득을 구하고자 하며, 이를 위해 몬테 카를로 시뮬레이션(Monte Carlo Simulation)을 이용하였다[23]. 몬테카를로 시뮬레이션은 무작위로 추출된 난수(Random Number) 를 이용하여 원하는 파라미터의 값을 확률적으로 구하는 알고 리즘 및 시뮬레이션 방법을 의미한다. 특히, 이 방법은 주어진 문제의 해석적인 해(Analytical Solution)를 구할 수 없거나 풀 이가 복잡한 경우, 해를 근사적으로 계산할 때 사용된다. 본 연 구에서는 몬테카를로 시뮬레이션을 통해 최적으로 계산하고 자 하는 비용을 다음과 같이 정의하였다.

Je=k=0Wfz1((xkxref,k)2+(ykyref,k)2)+z2(ψkψref,k)2Jc=k=0Wf|δk|Jtotal=αJe+βJc(11) 

식 (11)에서 경로 추종 오차 비용(Je )은 각각의 제어기를 이 용하여 한 번의 경로 추종 시행(Trial)에서의 누적된 경로 추종 비용을 나타내며 거리 오차 비용과 방위 오차 비용으로 구성 된다. xk, ykψk는 차량의 현재 위치와 방위이며, ref, k 첨 자는 매 제어 순간(k)의 목표 경로의 정보를 의미한다. z1와 z2은 오차 비용에 대한 가중치이고, 실험적으로 결정된 값으 로 가중치에 따라서 추종 오차 비용이 달라질 수 있으며 본 실 험에서는 1로 가정하였다(z1 = 1, z2 = 1). wf는 목표 경로 점 개수이다. ∇δk는 제어 입력의 변화 값이고 Jc는 제어 입력의 변화 비용을 의미하며 일반적으로 제어 노력(Control Effort)이 라고도 불린다. Jtotal 비용은 JcJe에 적절한 가중치를 곱해 더하였다(α = 1, β = 0.1). 몬테카를로 시뮬레이션은 Jtotal를 최소로 하는 제어 입력을 구하기 위해 각 제어기별 제어 이득 관련 파라미터에 난수를 입력한 경로 추종 시뮬레이션으로써 각각 1천 회씩 수행되었다.

몬테카를로 시뮬레이션은 각 제어기가 최소(Minimum value, 빨간 원) 비용을 가질 때의 각 제어 입력 파라미터를 결정하였 다[Fig. 5]. 주차 경로는 전방 경로와 후방 경로로 구성되어 있 으며, 경로 추종 비용(Jtotal)을 계산하는 구간은 후방 경로 추종 구간에 국한하였다. [Fig. 5]에서 가로축은 시행 횟수이다. 세로 축은 식 (11)에서 정의한 비용 Jtotal를 의미하며 파란 점 하나가 한번의 시행을 의미한다. 본 연구에서 사용된 비용은 절대적이 지 않고, 비용을 정의하기에 따라 각 제어기의 비용이 달라지 며, 이에 대한 각 제어기별 제어 파라미터 값도 변할 수 있다.

[Fig. 5]

Monte Carlo simulation of path following methods (Left: Kanayama, Mid: Preview, Right: MPC)

Kanayama 제어기에는 식 (2)에서 KyKθ 두 파라미터에 각각 0.1 ~ 10.0 범위로 uniform 분포의 난수를 발생시켰다. Uniform 분포를 이용한 이유는 최적의 제어 파라미터는 특정 구간에 동일한 확률로 존재함을 가정했기 때문이다. 몬테카를 로 시뮬레이션을 통해서 나온 Kanayama 제어기의 최적 파라 미터(Ky,Kθ )는 6.993, 5.099이다.

Preview 제어기에서는 식 (6)에서 확인할 수 있듯이, 예견 거리 l과 오차를 줄이는 수렴 속도 이득 파라미터인 λ에 대해 서 각각 uniform 분포의 난수를 발생시켰다(0.1~ 3.0, 5~15). Preview 제어기의 l은 예견 거리를 의미하기 때문에 0보다 커 야 한다. 주차 경로는 길이가 짧기 때문에, 주차 경로 추종 시뮬 레이션을 통해 실험적으로 최적 파라미터의 분포 범위를 정하 였다. Preview 제어기의 최적 파라미터(l, λ)는 0.528, 6.31이다.

MPC 제어기에 대해서는 경로 추종 가중 파라미터인 Q행렬 (3x3 행렬, 양의 정-부호 행렬)에서 3개의 파라미터 값과 제어 입 력 가중 파라미터인 R행렬(2x2 행렬, 양의 정-부호 행렬)에 대한 1개의 파라미터, 총 4개의 파라미터에 uniform 분포의 난수를 발 생시켰다(Q0:1~100, Q1:1~100, Q2:1~50, R1:0.001~0.1). Q0, Q1, Q2는 Q행렬의 대각선 성분이다. R0과 R1은 각각 R의 대 각 성분 값이며, 속력 제어 입력에 관여하는 값인 R0은 1로 설 정하였다. 조향 각에 대한 가중치 파라미터인 R1은 충분한 제 어 입력으로 오차를 빨리 줄이기 위해 값 범위를 0.1 이하로 정 하였다. 몬테카를로 시뮬레이션을 통해 얻은 MPC 제어기의 최적 파라미터(Q0, Q1, Q2, R1)는 65.640, 60.916, 22.659, 0.027이다. 세 제어기는 정-속력(3km/h) 주행을 가정하였고, 전방 주행을 하다가 전/후진 전환 지점에서는 멈추고 후방 주 행을 하였다.

몬테카를로 시뮬레이션 결과를 통해 얻은 최적의 파라미터 값을 이용해서 주차 경로 추종을 수행한 결과는 [Fig. 6]에서 확인할 수 있다. [Fig. 6] 의 첫 번째 행부터 세 번째 행까지 순 서대로 각각 Kanayama, Preview, MPC 제어기의 경로 추종 결 과를 의미한다. [Fig. 6] 의 첫 번째 열은 세 가지 주차 경로 추 종 방법 별 경로 추종을 수행한 궤적을 나타내며, 두 번째 열은 각 경로 추종을 수행 할 때, 주차 목표점 근처에서 추종된 경로 를 확대한 것이다. 일반적인 자율 주행 경로 추종과 달리, 주차 경로 추종은 주차 목표점에서의 최종 오차가 주차 성공 여부 에 중요한 역할을 하기 때문에 주차 목표점에서의 오차를 관 찰할 필요가 있다. 세 번째 열은 각 제어기의 제어 입력을 의미 하고 네 번째 열은 제어 입력 변화율이다.

[Fig. 6]

Parking path following results by using the optimum control inputs which are acquired by the Monte Carlo simulation (Top row: Kanayama, Middle row: Preview, Bottom row: MPC)

세 가지의 제어 방법을 이용한 주차 경로 추종 결과는 [Table 1]에 정리되었다. [Table 1]에서 보면, Preview와 MPC 제어기가 평균 거리 오차 값이 1 cm 내외로 확인되었으며, 평 균 방위 오차는 MPC가 가장 적었다. 또한, 주차 목표 지점에 서의 최종 거리 오차는 Preview가 가장 적었으며, MPC가 주차 목표 지점에서의 가장 적은 최종 방위 오차를 보였다. 그러나, [Fig. 6]의 네 번째 열에서 확인할 수 있듯이, MPC 방법의 제어 입력 변화율이 세 가지 제어 방법 중 가장 넓은 분포를 보이고 있고 제어 입력 비용이 가장 크다(Kanayama: 7.87, Preview: 7.93, MPC: 8.69). 이는 그만큼 차량 핸들 각도에 큰 변화가 있 음을 의미한다. 이런 부분은 MPC 제어 방법을 설계할 때, 제 어 입력의 변화율을 고려한 제약 조건을 넣음으로써 개선할 수 있는 부분이다.

Parking path following results by using three methods with the optimum control parameters which are calculated by the Monte Carlo simulation

4.2 초기 오차에 대한 세 가지 경로 추종 알고리즘 성능 비교 분석 실험

본 절에서는 4.1장에서 수행한 각 제어기별 주차 경로 추종 을 위한 최적의 제어 파라미터를 이용하여 경로 추종 실험을 수행하였으며 초기 경로 추종 오차가 있는 상황을 가정하였 다. 이렇게 목표 경로에서 떨어진 지점에서 경로 추종을 시작 하는 것은 제어기의 추종 성능을 확인하는 하나의 방법이다. 초기 경로 추종 오차에 대한 성능은 1,000가지의 오차 자세 (Error Posture)에 대한 경로 추종의 시뮬레이션을 수행하여, 각 제어기 마다 성능의 변화를 통해 확인되었다. 여기서 오차 자세란, 주차 경로의 전/후진이 교차되는 하나의 점(목표 x,y, 및 orientation)을 기준으로 일정한 범위(±0.3 m의 거리 오차, ±10°의 방위 오차) 값을 더해서 임의로 만든 자세를 의미하며 차량은 이러한 1,000가지 초기 오차를 가정한 자세에서 후방 경로 추종을 시작하게 된다. [Fig. 7]의 왼쪽 그림은 4.1절에서 수행한 몬테카를로 시뮬레이션에서의 전방 및 후방 목표 경로 이며 빨간 점에서 차량이 전방 주차 경로 추종을 시작하고 ‘Goal Point’가 주차 목표점이다. 오차 자세에서의 시뮬레이션 은 ‘Switching point’라고 표기된 부분 주변에서 시작된다. [Fig. 7] 오른쪽 그림에서의 빨간 점은 차량의 전/후진 전환 지 점에서의 목표 위치를 의미하며, 파란 화살표는 그 순간의 목 표 방위를 의미한다. 초록 점들은 빨간 점 중심으로 임의로 생 성한 1,000가지의 오차 위치를 의미하며, 검은 화살표는 이에 대한 각각 차량의 시작 방위를 의미한다. [Fig. 8]은 경로 추종 제어기별 초기 오차 자세에서의 경로 추종 오차 비용(=거리 오차+방위 오차)에 대한 box 그래프이며 Preview 제어기의 최 소 비용 값이 가장 적었다(Kanayama: 9.464, Preview: 2.340, MPC: 3.154). 그러나, 경로 추종 오차 비용에서 75% 위치의 비 용 값(Kanayama: 42.252, Preview: 50.374, MPC: 24.018) 및 최 대 비용 값(Kanayama: 86.785, Preview: 103.544, MPC: 49.048) 은 세 제어기 중 Preview 가 가장 높다. 4.1절의 몬테카를로 시 뮬레이션을 통해 얻은 최적 파라미터 기반으로 목표 경로 점 과 차량이 가까울 때(초기 거리 및 방위 오차: 0.03 m, 3°)는 Preview 제어기의 경로 추종 오차 비용이 가장 적었으나, 목표 경로 점과 차량이 가깝지 않은 경우[Fig. 8]의 Preview 제어기 평균 오차 값은 35.198로 가장 높았고, 그 다음으로 Kanayama (31.502)와 MPC (18.371) 순서이다.

[Fig. 7]

Parking path and the parking scenario (left) and 1,000 error postures trials (right)

[Fig. 8]

Parking path following error distribution with respect to the error postures (box-plot)

초기 오차가 있는 상황에서 서로 다른 세 가지의 곡률 값을 가진 경로를 추종한 성능도 확인하였다[Fig. 9]. 곡률은 (1/9 m) ≅ 0.11, (1/11 m) ≅ 0.09, (1/13 m) ≅ 0.07, 이며 초기 오차는 각각 (0.60 m, 8.5°), (0.59 m, 7.3°), (0.57 m, 6.0°)이다. 평균 거 리 오차와 평균 방위 오차는 (Kanayama), (Preview), (MPC) 순 서로 0.11 곡률일 때에는 (0.09 m, 2.5°), (0.11 m, 3.1°), (0.08 m, 2.6°)이고, 0.09 곡률일 때에는 (0.06 m, 2.3°), (0.09 m, 2.6°), (0.05 m, 2.2°), 0.07 곡률일 때에는 (0.06 m, 2.1°), (0.07 m, 2.7°), (0.05 m, 2.1°)이다. 이 결과는 4.1절의 몬테카를로 시뮬레이션 을 통해 얻은 결과와 같은 경향을 지니며, 곡률이 커질수록 경 로 추종 오차가 늘어남을 확인할 수 있었다.

[Fig. 9]

Parking path following results with the three curvatures

4.3 제어 입력에 외란이 있을 때의 세 가지 경로 추종 알 고리즘 성능 비교 분석 실험

본 절에서는 차량에서 실제 조향 제어 입력이 인가되는 부 분인 액추에이터에 노이즈가 있을 때의 세 가지 경로 추종 알 고리즘의 성능을 평가하기 위한 시뮬레이션을 진행한다. 이 실험은 기존의 후방 목표 경로를 추종하면서, 제어 성능을 확 인하기 위해 목표 점 기준([Fig. 7] 오른쪽 그림에서의 빨간 점), x축으로 0.258 m, y축으로 0.067 m, 방위로 –3.43° 더한 초 기 오차 자세에서 후방 경로 추종을 하는 것이다.

제어 입력에 외란을 고려한 시뮬레이션은 기존 제어 입력 에 외란을 인가하는 형태(δinput = δoriginal + δdisturbance)로 수 행됐다. δoriginal 은 각 제어 방법에서 구한 제어 입력이다. 여기서 δdisturbance 값은 평균 0이고, 표준 편차 (δmax4)2 또는 (δmax4)2 값을 이용했고 가우시안 분포(Gaussian Distribution) 형태를 가진다. 두 개의 가우시안 분포를 띄는 제어 입력 외란을 고려 한 후방 경로 추종 시뮬레이션 결과는 각각 [Fig. 10]와 [Fig. 11]이다. 두 그림에서의 각 행은 세 가지 경로 추종 방법이고, 첫 번째 열은 후방 경로를 추종한 궤적, 두 번째 열은 제어 입력 값이며, 세 번째 열은 거리 오차 값이다. 제어 입력 값은 입력 외란 값이 더해지기 때문에, 최대 조향각 값(δmax=540°)으로 제한하였다.

[Fig. 10]

Path following results with input disturbances (δdisturbance∼N(0, (δmax4)2))

[Fig. 11]

Path following results with input disturbances (δdisturbance∼N(0, (δmax2)2))

세 가지 경로 추종 방법의 추종 성능에 대한 정량적인 결과 로써 평균 거리 및 방위 오차와 주차 경로 추종의 가장 마지막 주차 지점에서의 거리 및 방위 오차를 Table로 정리하였다. [Table 2]는 제어 입력 외란이 없을 때, [Table 3]은 제어 입력 외란 값들의 표준 편차 값이 (δmax4)2 일 때의 결과 값이고, [Table 4]는 제어 입력 외란 값들의 표준 편차 값이 (δmax2)2 일 때의 결과를 보여준다. 제어 입력 외란이 없는 실험 결과인 [Table 2]에서 보면, 평균 거리 오차는 MPC가 가장 작으며, 방 위 오차는 Kanayama 방법이 가장 작다. 또한, 세 가지 방법으 로 모두 주차 경로 추종 완료 지점에서의 거리 및 방위 오차를 보면, 2 cm, 0.5° 이하로 경로가 추종 됨을 확인할 수 있다. 그러 나, [Table 3]에서 볼 수 있듯이 제어 입력 외란이 가해질 때, 세 가지 경로 추종 방법 모두 거리 및 방위 오차 평균 값이 증가하 는 경향을 볼 수 있으며 특히, Preview 제어기의 방위 오차 값 이 가장 많이 증가된 것을 확인할 수 있다. 하지만, 주차 목표 점에서의 거리 및 방위 오차는 세 가지 방법 모두 2 cm 내외의 거리 오차와 1°이하의 방위 오차를 보이기 때문에 주차 경로 추종이 적절하게 이루어졌음을 확인할 수 있다.

Path following errors of a parking path without the input disturbance

Path following errors of a parking path with the input disturbance (δdisturbance∼N(0, (δmax4)2))

Path following errors of a parking path with the input disturbance (δdisturbance∼N(0, (δmax2)2))

[Table 4]는 제어 입력 외란을 더 크게 입력한 것으로 외란 값들의 표준 편차 값이 (δmax2)2 일 때의 경로 추종 결과를 의 미하며 세 가지 경로 추종 방법의 오차 평균값은 증가하였다. Preview 제어기는 제어 입력 외란이 없을 때를 기준으로 하여 가장 큰 비율로 오차 평균값이 증가하였다(거리 오차: 15.7%, 방위 오차: 34.6%). 반면에, Kanayama 제어기는 세 가지 방법 중에서 가장 낮은 비율(거리 오차: 0.9%, 방위 오차 1.8%)로 오 차 값이 증가했기 때문에, 세 가지 방법 중에서 제어 입력 외란 에 가장 강인함을 보였다.

4.4 초기 경로 추종 오차와 제어 입력에 외란이 있을 때, 세 가지 경로 추종 알고리즘 성능 비교 분석 실험

본 절에서는 4.1 절에서 몬테카를로 시뮬레이션을 통해 구 한 최적 제어 입력 파라미터를 이용하고 4.2 절에서 정의한 1,000가지의 초기 오차 자세에서, 4.3 절에서 언급된 제어 입력 외란이 존재하는 시나리오에서 경로 추종 성능을 확인하고자 한다. 여기서 이용한 제어 입력 외란은 평균이 0이고, 표준 편차 값이 (δmax2)2 인, 가우시안 분포를 이용하였다.

세 가지 경로 추종 방법을 이용한 결과에 대한 box 그래프 는 [Fig. 12]에서 확인할 수 있다. 제어 입력 외란이 없는 [Fig. 8]과 비교하면 Preview 제어기와 MPC 제어기의 오차 분포가 더 넓어졌음을 확인할 수 있다. 이에 반해, Kanayama 제어기는 제어 입력 외란이 있을 때와 없을 때와의 큰 차이가 없었다. Preview 제어기는 오차 중간값이 크게 올랐으며, MPC 제어기도 오차의 중간 값과 최대 값이 각각 증가되었음을 확인할 수 있다.

[Fig. 12]

Parking path following error distribution with error postures and input disturbances(box-plot)

제어 입력 외란의 영향에 대한 오차 비용 증가율은 [Table 5] 에 정리하였다. 제어 입력 외란이 없을 때, MPC가 경로 추종 오차 비용이 가장 낮다. 하지만, 제어 노력에 해당하는 Control Cost 비용이 큰 것으로 보아, 제어 입력 변화율이 큰 것을 확인 할 수 있었다. 제어 입력 외란이 있을 때, Preview 제어 방법이 가장 큰 오차 비용을 보였고 제어 입력 외란이 없을 때 비해서 가장 큰 비용 증가율을 보였다. 제어 입력 외란이 있어도 MPC 의 제어 방법은 가장 적은 오차 비용을 보였으나 외란이 없을 때와 마찬가지로 가장 큰 제어 노력 비용을 보였다. 이러한 부 분은 MPC 제어 방법에서 제어 입력 변화율에 대한 제약 조건 을 이용하면 제어 노력 비용의 감소를 기대할 수 있으나 제어 입력의 변화율 제약은 곧 경로 추종 성능에도 영향을 미칠 수 있는 상충(Trade-off)관계가 있기 때문에 제어기 설계자는 이 러한 부분을 고려해야 한다. 제어 입력 외란에 대해서 세 가지 방법 중 가장 강인한 제어 방법은 Kanayama 제어기였으며, 제 어 오차 비용과 제어 노력 비용에서 가장 변화가 적었다.

Path following results with error postures and the input disturbance (δdisturbance∼N(0, (δmax2)2))


5. 결 론

본 연구는 기존에 경로 추종 방법으로 제안되었던 알고리 즘들의 특징에 대해 설명을 하고 자율 주차에 적용될 수 있는 세 가지 경로 추종 알고리즘(Kanayama, Preview 및 MPC)을 소개하였다. 주차 경로와 같이 곡률이 크고, 경로 길이가 짧아 서 경로 끝 점이 존재하는 주행 상황에서, 세 가지 경로 추종 알 고리즘의 정성적/정량적 비교 분석이 수행되었다. 우선, 세 가 지 경로 추종 방법의 최적 제어 파라미터를 결정하기 위해 몬 테카를로 시뮬레이션이 수행되었다. 그리고 자율 주차 주행 중 차량 방향 전환 지점에서의 초기 오차에 대해 각 제어기 별 성능이 확인되었다. 또한, 차량의 핸들을 제어할 때, 조향 액추 에이터에서 발생될 수 있는 노이즈를 제어 입력 외란으로 정 의하고, 외란 크기 별 주차 경로 추종 성능도 확인하였다. 마지 막으로, 초기 오차와 제어 입력 외란이 동시에 존재하는 환경 에서 경로 추종 성능을 비교 분석하였다. 세 가지 경로 추종 방 법의 시뮬레이션 결과를 보면, 차이가 크지 않기 때문에 모두 주차 제어에 사용 가능하지만, 몇 가지 특징들이 있고 이에 대 한 각 경로 추종 알고리즘들의 장/단점을 다음과 같이 언급하 고자 한다.

Kanayama 제어 방법은 추종 오차를 보상하는 Feed-back 부 분과 목표 경로 점들의 곡률을 이용한 Feed-forward 부분으로 제어 입력이 구성 되어 있다. 이 방법은 세 가지 경로 추종 알고 리즘 중에, 가장 큰 경로 추종 오차를 보이지만, 세 알고리즘 중에서 구현이 간단하고, 주차 목표점에서도 주차 경로 추종 의 성능이 각각 4 cm, 1° 내외의 거리 및 방위 오차를 보이기 때 문에 주차 경로 추종 알고리즘으로 적합함을 확인하였다. 특 히, 이 방법은 제어 입력 외란이 존재 할 때에도 세 가지 알고리 즘 중 가장 강인한 경로 추종 성능을 보였으며, 세 가지 경로 추 종 방법 중에서 제어 노력 비용이 가장 적기 때문에 효율적으 로 주차 경로 추종을 수행할 수 있다.

Preview 제어기는 일정한 예견 거리에서의 목표 점과 현재 차량에서 가장 가까운 목표 점에서의 경로 추종 오차를 줄일 수 있는 제어 방법으로써 몬테카를로 시뮬레이션을 통해 나온 경로 추종 성능은 세 알고리즘 중에서 가장 나았다. 그러나, 이 방법은 차량의 방향이 전환되는 위치에서 오차가 발생했을 때 세 알고리즘 중 제어 성능이 가장 큰 비율로 감소 되었으며 제 어 입력 외란이 있을 때, 경로 추종 비용의 변화율이 가장 높아 서 제어 입력 외란에 취약함을 보였다.

MPC 제어기는 미리 정의해 놓은 비용을 최소화하면서 동 시에 제약 조건을 고려하여 최적 제어 입력을 구하는 방식이 다. 세 가지 알고리즘 중 MPC 제어기는 초기 오차가 있을 때와 제어 입력 외란이 있을 때 모두 가장 적은 추종 오차 비용을 보 였고, 주차 목표점에서도 거리 오차 및 방위 오차가 가장 적었 다. 그러나, 세 가지 제어기 중, Kanayama 제어기는 제어 입력 외란에 가장 강인한 반면, MPC는 제어 입력 외란이 있을 때 추 종 오차 비용의 증가율이 더 높았다. 또한, MPC는 제어 노력 비용에서 세 제어기 중, 가장 많은 비용을 사용 하였으며 이는 차량의 조향 엑추에이터에 상대적으로 큰 부하가 걸릴 수 있 고, 조향의 변화는 곧 차량의 방위의 변화를 유발한다. 이러한 변화는 차량의 횡 방향 가속도를 생성할 수 있기 때문에 결론 적으로, 승차감에도 악영향을 미칠 수 있다. MPC 제어기는 초 기 경로 추종 오차와 제어 입력 외란이 있음에도 불구하고, 주 차 목표 점에서 2 cm, 1°이하의 경로 추종 오차를 보여 주차 경 로 추종 알고리즘으로 적합함을 보였다.

본 연구의 후속 연구로써 위치 추정 오차가 있는 실제 차량 에서도 주차 경로 추종 성능을 확인 하고자 한다.

References

  • M. Kim and J. Park, “Autonomous Parking using Sampling-Based Path Planning and Model Predictive Control,” The Korean Society of Automotive Engineers Annual Spring Conference, pp. 879-901, 2018, [Online], https://www.dbpia.co.kr/journal/articleDetail?nodeId=NODE07546720.
  • M. Kim, G. Im, J. Ahn, M. Kim, and J. Park, “Autonomous parking algorithm using automatic selection of forward and backward switching points via model predictive control,” The Korean Society of Automotive Engineers Annual Autumn Conference, pp. 646-649, 2018, [Online], https://www.dbpia.co.kr/journal/articleDetail?nodeId=NODE07593207.
  • S. Lee, M. Kim, Y. Youm, and W. Chung, “Control of a car-like mobile robot for parking problem,” 1999 IEEE International Conference on Robotics and Automation (Cat. No.99CH36288C), Detroit, MI, USA, 1999.
  • R. W. Roger, “Asymptotic stability and feedback stabilization,” Differential Geometric Control Theory, pp, 181-191, 1983, [Online], http://citeseerx.ist.psu.edu/viewdoc/summary?
  • M. Kim, S. Shin, and J. Park, “Study on vehicle lateral control for backward driving,” 2016 13th International Conference on Ubiquitous Robots and Ambient Intelligence (URAI), Xi’an, China, 2016. [https://doi.org/10.1109/URAI.2016.7625734]
  • I. E. PAROMTCHIK and C. LAUGIER, “Autonomous parallel parking of a nonholonomic vehicle,” Conference on Intelligent Vehicles, Tokyo, Japan, pp. 13-18, 1996.
  • S. Thrun, M. Montemerlo H. Dahlkamp, D. Staven, A. Aron, J. Diebel, P. Fong, J. Gale, M. Halpenny, K. Lau, C. Oakly, M. Palatucci, V. Pratt, P. Stang, S. Strohband, C. Dupont, L.-E. Jendrossek, C. Koelen, C. Markey, C. Rummei, J. van Niekerk, E. Jensen, P. Alessandrini, G. Bradski, B. Davies, S. Ettinger, A. Kaehier, A. Nefian, and P. Mahoney, “Stanley: The robot that won the DARPA Grand Challenge,” Journal of field Robotics, vol. 23, no. 9, pp. 661-692, 2006. [https://doi.org/10.1002/rob.20147]
  • R. Wallace, A. Stentz, C. Thorpe, H. Moravec, W. L. Whittaker, and T. Kanade, “First Results in Robot Road-Following,” International Joint Conference on Artificial Intelligence, 1985, [Online], https://www.semanticscholar.org/paper/First-Resultsin-Robot-Road-Following-Wallace-Stentz/aed962d06b081820cb3481fafa5a59568fca4764.
  • The 2005 DARPA grand challenge: the great robot race, M. Buehler, K. Iagnemma, and S. Singh eds., Springer Nature, Switzerland, 2007, [Online], https://www.springer.com/gp/book/9783540734284.
  • R. Rajamani, C. Zhu, and L. Alexander, “Lateral control of a backward driven front-steering vehicle,” Control Engineering Practice, vol. 11, no. 5, pp. 531-540, 2003. [https://doi.org/10.1016/S0967-0661(02)00143-0]
  • Y. Kanayama, Y. Kimura, F. Miyazaki, and T. Nogu, “A stable tracking control method for an autonomous mobile robot,” IEEE International Conference on Robotics and Automation, Cincinnati, OH, USA, pp. 384-389, 1990.
  • W. Yang, L. Zheng, Y. Li, Y. Ren, and Y. Li, “A Trajectory Planning and Fuzzy Control for Autonomous Intelligent Parking System,” WCX17: SAE World Congress Experience, 2017. [https://doi.org/10.4271/2017-01-0032]
  • J. Keighobadi and Y. Mohamadi, “Fuzzy Sliding Mode Control of a Non-Holonomic Wheeled Mobile Robot,” 2011 IEEE 9th International Symposium on Applied Machine Intelligence and Informatics (SAMI), Smolenice, Slovakia, 2011. [https://doi.org/10.1109/SAMI.2011.5738888]
  • Z. Fan and H. Chen, “Study on Path Following Control Method for Automatic Parking System Based on LQR,” Int. J. Passeng. Cars - Electron. Electr. Syst., vol. 10, no. 1, pp. 41-49, 2017. [https://doi.org/10.4271/2016-01-1881]
  • M. Brezak, P. Ivan, and P. Nedjeljko, “Experimental comparison of trajectory tracking algorithms for nonholonomic mobile robots,” 2009 35th Annual Conference of IEEE Industrial Electronics, Porto, Portugal, 2009. [https://doi.org/10.1109/IECON.2009.5415188]
  • D. HeB, M. Althoff, and T. Sattel. “Comparison of trajectory tracking controllers for emergency situations,” 2013 IEEE Intelligent Vehicles Symposium (IV), Gold Coast, QLD, Australia, 2013. [https://doi.org/10.1109/IVS.2013.6629465]
  • D. Calzolari, B. Schürmann, and M. Althoff, “Comparison of trajectory tracking controllers for autonomous vehicles,” 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC), Yokohama, Japan, 2017. [https://doi.org/10.1109/ITSC.2017.8317800]
  • S. Dominguez, A. Ali, G. Garcia, and P. Martinet, “Comparison of lateral controllers for autonomous vehicle: Experimental results,” 2016 IEEE 19th International Conference on Intelligent Transportation Systems (ITSC), Rio de Janeiro, Brazil, 2016. [https://doi.org/10.1109/ITSC.2016.7795743]
  • J. Mattingley and S. Boyd, “CVXGEN: A code generator for embedded convex optimization,” Optimization and Engineering, vol. 13, no. 1, 2012. [https://doi.org/10.1007/s11081-011-9176-9]
  • E. Rohmer, S. P. N. Signgh, and M. Freese, “V-REP: a Versatile and Scalable Robot Simulation Framework,” 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems, Tokyo, Japan, 2013. [https://doi.org/10.1109/IROS.2013.6696520]
  • Kim Minsung, Github, [Online], https://github.com/WestsideMS, Accessed: Feb. 04, 2020.
  • M. Mark, I. A. Șucan, and L. E. Kavraki, “Benchmarking Motion Planning Algorithms: An Extensible Infrastructure for Analysis and Visualization,” IEEE Robotics & Automation Magazine, vol. 22, no. 3, pp. 96-102, 2015, [https://doi.org/10.1109/MRA.2015.2448276]
  • F. A. Cheein and G. Scaglia, “Trajectory tracking controller design for unmanned vehicles: A new methodology,” Journal of Field Robotics, vol. 31, no. 6, pp. 861-887, 2014, [https://doi.org/10.1002/rob.21492]
김 민 성

2010 중앙대학교(공학사)

2011~현재 서울대학교 융합과학기술대학원 석사, 박사 통합과정

관심분야: Autonomous Vehicle, Motion Control, Optimal Control

임 규 범

2018 국민대학교(공학사)

2018~현재 서울대학교 융합과학기술대학원 석사 과정

관심분야: SLAM, Autonomous Vehicle

박 재 흥

1995 서울대학교 항공우주공학과(공학사)

1999 서울대학교 항공우주공학과(공학석사)

2006 Stanford University Aero/Astro(공학박사)

2009~현재 서울대학교 융합과학기술대학원 교수

관심분야: Robot-environment Interaction, Contact Force Control, Multi-Contact Control, Whole-body Dynamic Control, Bio-mechanics

[Fig. 1]

[Fig. 1]
Kanayama error posture: error posture with respect to the Kanayama controller

[Fig. 2]

[Fig. 2]
Geometry relationship of the preview controller

[Fig. 3]

[Fig. 3]
Kinematic bicycle model for the MPC

[Fig. 4]

[Fig. 4]
V-rep simulator environment

[Fig. 5]

[Fig. 5]
Monte Carlo simulation of path following methods (Left: Kanayama, Mid: Preview, Right: MPC)

[Fig. 6]

[Fig. 6]
Parking path following results by using the optimum control inputs which are acquired by the Monte Carlo simulation (Top row: Kanayama, Middle row: Preview, Bottom row: MPC)

[Fig. 7]

[Fig. 7]
Parking path and the parking scenario (left) and 1,000 error postures trials (right)

[Fig. 8]

[Fig. 8]
Parking path following error distribution with respect to the error postures (box-plot)

[Fig. 9]

[Fig. 9]
Parking path following results with the three curvatures

[Fig. 10]

[Fig. 10]
Path following results with input disturbances (δdisturbance∼N(0, (δmax4)2))

[Fig. 11]

[Fig. 11]
Path following results with input disturbances (δdisturbance∼N(0, (δmax2)2))

[Fig. 12]

[Fig. 12]
Parking path following error distribution with error postures and input disturbances(box-plot)

[Table 1]

Parking path following results by using three methods with the optimum control parameters which are calculated by the Monte Carlo simulation

[Table 2]

Path following errors of a parking path without the input disturbance

[Table 3]

Path following errors of a parking path with the input disturbance (δdisturbance∼N(0, (δmax4)2))

[Table 4]

Path following errors of a parking path with the input disturbance (δdisturbance∼N(0, (δmax2)2))

[Table 5]

Path following results with error postures and the input disturbance (δdisturbance∼N(0, (δmax2)2))