Journal Archive

Journal of Korea Robotics Society - Vol. 16 , No. 3

[ ARTICLE ]
The Journal of Korea Robotics Society - Vol. 16, No. 3, pp. 250-259
Abbreviation: J. Korea Robot. Soc.
ISSN: 1975-6291 (Print) 2287-3961 (Online)
Print publication date 31 Aug 2021
Received 04 Mar 2021 Revised 22 Apr 2021 Accepted 10 May 2021
DOI: https://doi.org/10.7746/jkros.2021.16.3.250

자율주차 상황에서 차량 구속 조건 고려에 따른 경로 계획 및 추종 성능의 비교 분석
김민수1 ; 안준우1 ; 김민성1 ; 신민용2 ; 박재흥

A Comparative Analysis of Path Planning and Tracking Performance According to the Consideration of Vehicle’s Constraints in Automated Parking Situations
Minsoo Kim1 ; Joonwoo Ahn1 ; Minsung Kim1 ; Minyong Shin2 ; Jaeheung Park
1PhD Student, Graduate School of Convergence Science and Technology, Seoul National University, Seoul, Korea (msk930512@snu.ac.kr)(joonwooahn@snu.ac.kr)(minsungkim@snu.ac.kr)
2Senior Researcher, Phantom AI Inc., Burlingame, California, USA (daniel@phantom.ai)
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)


CopyrightⓒKROS
Funding Information ▼

Abstract

Path planning is one of the important technologies for automated parking. It requires to plan a collision-free path considering the vehicle’s kinematic constraints such as minimum turning radius or steering velocity. In a complex parking lot, Rapidly-exploring Random Tree* (RRT*) can be used for planning a parking path, and Reeds-Shepp or Hybrid Curvature can be applied as a tree-extension method to consider the vehicle’s constraints. In this case, each of these methods may affect the computation time of planning the parking path, path-tracking error, and parking success rate. Therefore, in this study, we conduct comparative analysis of two tree-extension functions: Reeds-Shepp (RS) and Hybrid Curvature (HC), and show that HC is a more appropriate tree-extension function for parking path planning. The differences between the two functions are introduced, and their performances are compared by applying them with RRT*. They are tested at various parking scenarios in simulation, and their advantages and disadvantages are discussed by computation time, cross-track error while tracking the path, parking success rate, and alignment error at the target parking spot. These results show that HC generates the parking path that an autonomous vehicle can track without collisions and HC allows the vehicle to park with lower alignment error than those of RS.


Keywords: Automated Parking, Path Planning, Steering Function, Reeds-Shepp, Hybrid Curvature

1. 서 론

자율주차 기술은 차량 주변의 빈 주차 영역을 탐색하고, 현재 차량의 위치에서 빈 주차 영역으로 차량을 주차시키는 기술이다[1]. 특히, 주차장 환경은 일반 구조화된 도로에 비해 도로의 너비가 좁으며, 다양한 장애물이 복잡하게 존재하기 때문에, 자율주차 기술은 주차 경로 계획이 필요하다. 자율주차 경로 계획은 차량의 최소 회전 반경, 조향속도 등의 구속 조건을 고려해야하며, 차량이 주차장 내 복잡하게 놓인 장애물과 충돌 없이 작은 오차로 추종 가능하고, 주차 목표점에서 작은 위치 및 방향 오차로 도달 가능한 주차 경로를 생성해야한다.

기존에 연구되고 있는 자율주차 경로 계획 방법으로는 최적화 기반의 방법, 그리드(Grid) 탐색 기반의 Hybrid-A* 방법, 샘플링 기반의 Rapidly-exploring Random Tree* (RRT*) 방법이 있다. 최적화 기반의 경로 계획 방법은 경로 계획을 Optimal Control Problem (OCP)[2]으로 접근하여 주차 경로를 계획한다. OCP 방법은 빠른 경로 계획을 위해 주차장 내 장애물과 차량의 구속 조건이 컨벡스(convex) 함수로 정의되어야 하며, 장애물이 복잡하게 존재하는 주차장에서는 local minima에 빠지기 쉬운 단점이 있다. Hybrid-A* 방법은 configuration space를 그리드 단위로 구성하여 차량의 구속 조건을 고려하며 경로를 탐색하는 방법으로, 장애물이 적은 환경에서 빠르게 주차 경로를 계획할 수 있다[3]. 그러나, 장애물이 많은 복잡한 주차장에서는 주차 경로의 전후진 전환 횟수가 증가되어, 탐색 시간이 증가되는 단점이 있다.

RRT* 방법은 configuration space에서 랜덤하게 pose를 샘플링하며, 트리를 확장하여 주차 경로를 계획한다. 이때, 트리 확장 방법으로 조향 함수(steering function)를 적용하여 차량의 구속 조건이 고려될 수 있다. RRT* 방법은 configuration space를 빠르게 탐색할 수 있으며, 트리 확장 방법에 따라 차량의 구속 조건을 쉽게 고려할 수 있는 장점이 있어, 복잡한 주차장 환경에서 주차 경로 계획 방법으로 사용될 수 있다[4,5].

RRT*로 주차 경로 계획 시, 대표적으로 사용되는 트리 확장 방법은 Reeds-Shepp (RS)[6] 조향 함수가 있다. RS 조향 함수는 차량의 최소 회전 반경을 고려한 원호와 직선의 조합으로 두 pose를 연결하는 경로를 찾는 방법이다. RS 조향 함수는 전후진 전환을 고려하며, 적은 계산 속도를 갖는 장점이 있어 주차 경로 계획 시 사용된다. 최소 회전 반경뿐만 아니라 최대 조향속도까지 고려하는 Continuous Curvature (CC)[7] 조향 함수도 있다. CC 조향 함수는 클로소이드 곡선을 원호와 직선 사이에 구성하여, 원호와 직선 사이에서 곡률이 불연속인 경로를 생성하는 RS 조향 함수의 단점을 극복한다. 그러나, 주차 경로 계획 시 전후진 전환 지점에서도 곡률이 연속적인 경로를 생성하여, 경로의 길이가 길어지는 단점이 있다.

Hybrid Curvature (HC)[8]는 CC 조향 함수에서 전후진 전환 시, 곡률의 불연속을 허용하는 방법이다. 이에 따라, 주차 시 전후진 전환 지점에서 정지 후, 차량이 조향을 변화시킬 수 있는 것을 고려할 수 있다. 또한, 주차 경로에서 전후진을 포함한 경우, CC 조향 함수를 사용한 경로에 비하여 길이가 짧고, 전후진 전환 횟수가 줄어드는 장점을 갖는다. 이처럼 각 조향 함수에 따라 고려되는 차량의 구속 조건은 달라지며, 계산 속도, 경로의 길이 및 곡률에 차이가 존재한다. 결과적으로, 트리 확장 방법으로 사용되어 주차 경로를 계획할 때, 경로 계획 시간, 추종 성능 및 주차 성공률에 영향을 미치게 된다.

그러므로 본 논문에서는 조향 함수에 따른 RRT*의 주차 경로 계획 성능을 비교하고, HC 조향 함수가 작은 추종 오차와, 작은 위치 및 방향 오차로 주차를 완료하는 경로를 계획할 수 있음을 보인다. HC 조향 함수는, 전후진 전환 지점에서 곡률의 불연속을 고려할 수 있고 CC 조향 함수에 비해 적은 계산 속도를 갖는 RS 조향 함수와 비교된다. RS와 HC 조향 함수의 특징 및 차이가 설명되며, 본 논문에서는 이를 RRT*의 트리 확장 방법으로 사용하여 시뮬레이션 내 주차장 환경에서 주차 경로 계획 시간, 추종 시 cross-track 오차, 주차 성공률, 그리고 주차 목표점에서의 위치 및 방향 오차가 측정된다.

본 논문의 구성은 다음과 같다. 2장에서 RS와 HC 조향함수의 방법과 특징을 설명하고, 경로의 길이 및 계산 속도를 비교한다. 3장에서는 시뮬레이터 내 4가지의 주차 시나리오 및 실험 환경을 설명하고, 경로 계획 방법인 Informed RRT*와 경로 추종 방법인 Kanayama 제어기를 설명한다. 또한, 주차 경로 계획 시간, 추종 결과 및 주차 성공률을 바탕으로, 조향 함수 RS와 HC의 장단점을 기술한다. 4장에서는 본 논문을 결론짓고 future work를 언급한다.


2. 주차 경로 계획을 위한 조향 함수

본 절에서는 조향 함수 Reeds-Shepp (RS)과 Hybrid Curvature (HC)를 설명하고, 특징 및 차이를 서술한다. 조향 함수는 RRT*로 경로 계획 시 트리 확장 방법으로 사용되며, 차량의 구속 조건을 고려하는 Turn과 직선을 조합하여 두 pose를 잇는 경로를 만든다. 조향 함수는 키네마틱 바이시클 모델을 기반으로 한 차량 모델을 정의하여, 경로를 계획한다. 차량 모델을 이용하여, 차량의 구속 조건에 따른 Turn이 정의되며, 조향 함수는 이를 직선과 조합하여 조향 경로를 생성한다. RS는 원호(circular arc) 만을 사용하는 RS Turn, HC는 클로소이드 곡선(clothoid arc)까지 포함된 HC Turn을 사용하는 차이를 갖는다.

2.1 Reeds-Shepp (RS)

RS 조향 함수에서 사용되는 RS 차량 모델은 차량의 후륜 중심의 위치(x, y) 및 방향(θ)으로 정의되며, 식 (1)에 나타냈다.

x'y'θ'=cosθsinθtanϕLd(1) 

xʹ, yʹ는 단위 거리에 따른 위치 변화량을 의미하며, θʹ는 단위 거리에 따른 방향의 변화량을 의미한다. ϕ는 차량의 조향각, L은 차량의 전륜과 후륜 중심의 거리이며 d∈ {-1, 1}는 차량의 전후진 방향을 의미한다. RS 차량 모델은 차량의 최소 회전 반경을 구속 조건으로 고려하며, 다음 식 (2)와 같다.

tanϕLκmax,ϕ-ϕmax,ϕmax(2) 

ϕmax는 차량의 최대 조향각이며, κmax-1은 차량의 최소 회전 반경으로 정의된다. RS 조향 함수는 식 (1)-(2)를 이용하여, 최소 회전 반경을 고려하는 RS 경로를 생성한다.

RS 경로는 직선과 RS Turn으로 구성되며, 두 pose를 잇는 경로가 된다. RS Turn은 최소 회전 반경을 반지름으로 갖는 원호(circular arc)로서 [Fig. 1] 좌측에 나타냈으며, 차량은 최소 회전 반경을 따라 방향을 전환할 수 있게 된다. RS 경로에서 사용되는 조합을 [Table 1]에 RS families로 나타냈다. C는 {RS, HC} Turn, S는 직선을 의미한다. ‘ | ’는 전후진 전환을 의미한다. RS families로 조합된 경로 중, 길이가 가장 짧은 경로가 RS 경로로 선택된다.


[Fig. 1] 
Comparison of RS and HC Turn. RS Turn only consists of a circular arc with a minimum turning radius (κmax-1). HC Turn consists of clothoid and circular arcs. The red solid line represents a circular arc and the blue solid line represents a clothoid arc

[Table 1] 
Reeds-Shepp (RS) and Hybrid Curvature (HC) families. C denotes Turn, S a straight line, and | a switching
HC families
RS families Additional families at HC
C|C|C
C|CC
CC|C
CSC
CC|CC
C|CC|C
C|CSC
CSC|C
C|CSC|C
CCC
C|SC
CS|C
C|S|C

2.2 Hybrid Curvature (HC)

HC 조향 함수는 RS 조향 함수와 다르게, 차량의 최소 회전 반경뿐만 아니라 최대 조향속도 또한 고려한다. HC 차량 모델은 식 (1)인 RS 차량 모델에서 차량의 현재 곡률(κ)이 추가적으로 고려되며, 다음 식 (3)과 같다.

x'y'θ'κ'=cosθsinθtanϕL0d+0001σ(3) 

σ는 단위 거리에 따른 차량 곡률 변화량 κ'=ϕ'L cos2ϕ이며, 조향속도(ϕʹ)의 식이 되어 HC 차량 모델은 최대 조향속도를 고려할 수 있게 된다.

σ=ifswitching,σσmaxotherwise.(4) 

식 (4)에 HC 차량 모델의 구속 조건을 나타냈다. 차량 고유의 최대 조향속도(ϕʹmax)를 이용하여 곡률 변화량의 최댓값, σmax=ϕ'maxL cos2ϕ가 계산된다. HC 차량 모델은 전후진 전환 지점(switching)에서 차량이 정지 후, 조향각 회전이 가능함을 고려하게 되며, 전후진 전환 외 지점에서는 최대 조향속도를 고려하게 된다. HC 조향 함수는 식 (2)-(4)를 이용하여, HC 경로를 생성한다.

HC 경로는 직선과 HC Turn으로 구성된다. HC Turn은 클로소이드 곡선(clothoid arc)과 원호로 구성되며, [Fig. 1] 우측에 나타냈다. 클로소이드 곡선은 곡률이 거리에 따라 선형으로 변하는 곡선으로, 곡률의 변화량(σ)에 따라 곡선의 모양이 정해진다. HC Turn에서는 곡률의 변화량을 σmax로 고정하여 클로소이드 곡선을 생성하며, 식 (5)의 곡률 식을 이용하여 클로소이드 곡선을 생성한다.

θ's=κs=σmaxs(5) 

s는 곡선의 길이를 의미한다. [Fig. 1]의 우측, HC Turn에서 클로소이드 곡선의 시작점(s = 0)에서부터 경로의 곡률은 선형적으로 변화된다. 클로소이드 곡선의 끝 지점(s = send)에서는 최대 곡률(κ(send) = κmax)을 만족시키며, 최소 회전 반경의 원호를 따라 차량의 방향이 전환된다. HC 경로에 사용되는 조합, HC families는 RS families에서 실험[9]을 통해 추가된 4개의 조합(Additional families at HC)이 포함되며, [Table 1]에 나타냈다. RS 경로와 마찬가지로 HC families의 조합 중, 길이가 가장 짧은 조합이 HC 경로로 선택된다.

2.3 RS와 HC 조향 함수의 비교 및 특징

[Fig. 2]에 두 pose (qs, qg)를 연결하는 RS, HC의 CSC|C 경로를 나타냈다. 상단에는 CSC|C 경로를 나타냈으며, 하단에는 경로의 길이에 따른 곡률 그래프를 나타냈다. 붉은색 선은 원호, 녹색 선은 직선을 의미하며 클로소이드 곡선은 파란색 선으로 나타냈다. [Fig. 2]의 좌측, RS 경로는 원호와 직선으로 두 pose (qs, qg)를 연결한다. RS 경로는 최소 회전 반경을 반지름으로 갖는 원호 다음에 직선이 이어진다. 이에 따라, 이어진 부분에서 경로의 곡률이 최대 곡률(κmax)에서 0으로 불연속하게 변하게 된다.


[Fig. 2] 
CSC|C path of RS and HC (above), and curvature and arc length plot (below). qs and qg are start and goal poses. The red and blue solid lines represent circular and clothoid arcs (C), respectively. The green line represents a straight line (S)

[Fig. 2] 우측의 HC 경로는 전후진 전환 지점을 제외하고, 클로소이드 곡선을 포함하여 원호와 직선을 잇는다. 이는 곡률이 0인 구간에서 차량의 최대 곡률인 κmax까지, 곡률을 연속적으로 변하게 한다. 또한, 차량은 전후진 전환 지점에서 조향각의 회전이 가능하므로, RS 조향 함수와 마찬가지로 HC 조향 함수는 곡률의 불연속성 또한 고려하여 HC 경로를 생성한다.

두 조향 함수로, RRT*의 트리에서 샘플링된 pose로 확장할 때의 경로의 길이 및 계산 속도를 비교하기 위하여, RS와 HC 경로의 평균 길이 및 계산 속도를 [Table 2]에 나타냈다. 장애물이 없는 20 m × 20 m 공간에서 임의의 두 pose (qs, qg)를 104 번 생성하여 비교했다. 원호와 직선만을 이용한 RS 경로의 평균 길이는 클로소이드 곡선까지 포함한 HC 경로의 평균 길이보다 짧게 나타난다. 또한, 경로의 평균 계산 속도는 클로소이드 곡선의 계산을 포함한 HC가 RS 보다 크게 나타난다. RS, HC 경로의 길이 및 계산 속도의 차이는 주차 경로 계획 시간에 영향을 미치며, 이는 3.3 절에서 실험을 통해 설명된다.

[Table 2] 
Comparison of Reeds-Shepp and Hybrid Curvature path in a length and computation time
Length (m) Computation time (μs)
Reeds-Shepp 15.3731 32.538 (±21.403)
Hybrid Curvature 16.1805 439.535 (±125.031)


3. 실험 및 결과
3.1 실험 환경 및 주차 시나리오

주차 경로 계획 시 조향 함수 RS, HC의 성능 비교를 위해, CARLA 시뮬레이터[10]에서 주차장 환경을 구축하였고, 조향 함수 RS, HC를 RRT*의 트리 확장 방법으로 사용하여 주차 경로를 계획하였다. 제어기는 계획된 주차 경로와 시뮬레이터 내 차량의 위치 및 방향을 입력으로 받으며, 주차 경로를 추종하기 위한 차량의 조향각과 속도를 계산한다. 계산된 조향각과 속도로 시뮬레이터 내 차량을 제어하며 주차 실험을 진행하였다.

[Fig. 3]의 4가지 주차 환경에서 실험이 진행되었다. [Fig. 3(a)]의 Scenario 1은 도로의 너비가 넓은 환경에서 평행 주차이며, [Fig. 3(b)]의 Scenario 2는 도로의 너비가 넓은 환경에서의 직각 주차이다. [Fig. 3(c)]의 Scenario 3는 도로의 너비가 4 m 인 환경에서의 직각 주차이고, [Fig. 3(d)]의 Scenario 4는 주차 목표점 근처에 평행 주차 차량이 존재하는 환경에서의 직각 주차이다. 각 Scenario에서 100번의 경로 계획을 진행하여 RS와 HC의 성능을 비교하였다.


[Fig. 3] 
Experimental environments in CARLA simulator. (a) Scenario 1: parallel parking between two parallel-parked vehicles. (b) Scenario 2: perpendicular parking with a wide region. (c) Scenario 3: perpendicular parking with a narrow road (4 m). (d) Scenario 4: perpendicular parking with a parallel-parked vehicle. White and yellow solid lines represent parking paths by Informed RRT* with RS and HC, respectively

3.2 주차 경로 계획 및 추종 방법

본 실험에서는 주차 경로 계획 방법으로 Informed RRT*[11]를 사용하였다. Informed RRT*는 초기 경로를 찾기 전까지는 RRT*와 동일하게, 랜덤 샘플링을 진행한다. 초기 경로가 발견되면, Informed RRT*는 시작점과 목표점, 그리고 초기 경로의 길이를 이용하여 hyper-ellipsoid subset을 정의하고, 위 subset에서만 랜덤 샘플링을 진행한다. 위와 같은 차이로 Informed RRT*는 장애물이 다양하게 존재하는 주차장과 같은 환경에서, RRT* 보다 길이가 더 짧은 경로를 빠르게 찾을 수 있는 장점을 갖는다.

조향 함수에 이용되는 식 (1)-(4)의 파라미터는 시뮬레이터 내 차량을 바탕으로 설정되었다. 차량의 전륜과 후륜 중심 사이의 거리(L)는 2.7360 m 이고 차량의 최대 조향각은 540 deg 이며, 차량의 최대 조향속도는 180 deg/s, 최대 가속도는 0.56 m/s2 로 설정되었다. 이를 바탕으로, 차량의 최대 곡률(κmax)은 0.1786 m-1 , 곡률의 최대 변화량(σmax)은 0.1378 m-2 로 설정되었다. 본 실험에서는 Scenario 1-4의 경로 계획 시간을 각각 30.0 s, 5.0 s, 30.0 s, 90.0 s 로 제한하였다. 제한된 경로 계획 시간 이상의 시간이 걸린 경우, 주차 경로 계획은 실패로 가정하였다. 샘플의 충돌 검사는 차량의 크기 외 0.1 m의 여유 공간을 두어 진행하였다.

차량의 조향 제어는 Kanayama[12] 제어기를 사용하였다. Kanayama 제어기는 추종할 주차 경로 상에 차량의 현재 속도와 제어 주기를 고려하여 local 목표점을 정하고, local 목표점과 차량과의 위치 및 방향 차이를 이용한다. Kanayama 제어기는 식 (6)을 이용하여 차량 제어를 위한 조향각(ωKanayama)을 계산한다.

ωKanayama=ωr+vrKyye+Kesinθe(6) 

ωr은 local 목표점에서의 경로의 곡률을 이용한 조향각이며, 주차 경로 상에 차량이 정확히 위치 시 경로를 추종하기 위한 조향각이 된다. 식 (6)의 두번째 항은 차량과 추종할 주차 경로와의 위치 및 방향 차이를 고려한 조향각이다. ye는 차량의 후륜 중심(x, y) 기준, local 목표점과의 횡 방향 오차이며, θe는 local 목표점에서의 경로의 방향(tangent)과 차량의 방향(θ)과의 오차이다. vr은 차량의 목표 속도가 되며, Ky, Ke는 gain이 된다.

차량의 속도(vinput)는 주차 경로 상의 곡률 변화량 및 전후진 전환 지점을 고려하여 결정되며, 식 (7)과 같다.

vinput0.0         if pego=pswitchvmin      else if pego-pswitch2<τmaxvr1.0-Kvκr-κκmax,vminotherwise.(7) 

pego는 차량의 위치, pswitch는 주차 경로의 전후진 전환 지점을 의미한다. vmin는 최소 속도이다. κ는 현재 차량과 가장 가까운 경로 상의 곡률이며, κr은 local 목표점에서의 경로의 곡률 κmax는 차량의 최대 곡률이다. 이에 따라, κr-κκmax는 현재 차량이 추종하는 local 목표점에서의 곡률 변화율이 된다. Kv는 gain을 의미한다. 식 (7)에 따라, 차량의 위치가 전후진 전환 지점에 근접할수록 차량은 감속하며, 전후진 전환 지점에서는 조향 회전을 위해 3초간 정지한다. 그 외에는 경로의 곡률 변화율이 클수록 차량은 감속한다. 실험에서 식 (6)-(7)의 목표(vr) 및 최소 속도(vmin)는 각각 4.0 km/h 와 0.9 km/h 로 정하였다. 시뮬레이터에서 차량은 0.05 s 주기로 제어되며, gain인 Ky, Ke, Kv는 각각 2.0, 4.0, 10.0, τ는 2 m 로 설정하였다.

3.3 실험 결과 및 분석

주차 경로 계획 시 중요하게 평가되어야 할 요소는, 실시간성을 위해 적은 계산 속도로 경로 계획이 가능한지 여부와 차량이 작은 오차로 충돌 없이 추종할 수 있는 주차 경로를 생성할 수 있는지, 그리고 주차 목표점에 작은 위치 및 방향 오차로 주차를 성공할 수 있는지에 대한 것이 있다. 본 절에서는 위 요소들을 바탕으로 RS, HC 조향 함수의 장단점을 분석하고, 주차 경로 계획 시 HC 조향 함수가 사용되어야할 필요성을 보인다.

RS, HC 조향 함수의 성능을 정밀하게 분석하기 위하여 [Table 3]에, 각 Scenario에서 조향 함수 RS, HC 사용 시, Informed RRT*의 초기 주차 경로를 찾는 시간(time to the first solution), 경로 상 곡률의 불연속 지점의 수(number of curvature discontinuity), 경로의 길이(path length), 그리고 경로 계획 성공률(success rate)을 측정하여 나타냈다. 또한, [Table 4]에는 각 Scenario에서 생성된 주차 경로를 추종하였을 때, 평균 cross-track 오차(cross-track error), 주차 목표점에서의 평균 위치 및 방향 오차(lateral and orientation alignment error), 그리고 주차 성공률(parking success rate)을 나타냈다. cross-track 오차는 차량의 후륜 중심과 가장 가까운 경로 상 위치와의 거리로 측정되며, 주차 성공 여부는 주차선 내 차량이 위치했을 때로 정의되었다.

[Table 3] 
Experimental results of planning parking paths by Informed RRT*[11] with {RS, HC} steering functions. Time to the first solution, number of curvature discontinuity, path length, and success rate are listed with respect to each scenario
Time to the first solution
(mean±std) [s]
Number of curvature
discontinuity (mean±std) [-]
Path Length
(mean±std) [m]
Success Rate
[%]
RS HC RS HC RS HC RS HC
Scenario 1 0.04±0.04 2.66±3.90 5.17±1.35 4.12±1.59 17.22±2.47 28.01±10.15 85.00 22.00
Scenario 2 0.03±0.04 1.11±1.13 4.00±0.00 2.00±0.00 8.77±0.00 10.07±0.00 100.00 96.00
Scenario 3 1.64±4.27 5.38±7.06 9.16±2.48 6.22±2.13 10.91±0.97 15.55±3.09 79.00 23.00
Scenario 4 1.49±1.60 33.60±24.20 9.43±5.00 7.67±3.59 18.18±2.72 29.21±4.13 61.00 12.00

[Table 4] 
Experimental results of tracking parking paths by Kanayama[12] controller. Cross-track error, lateral / orientation alignment error and parking success rate are listed with respect to each scenario
Cross-track error
(mean±std) [cm]
Lateral alignment error
(mean±std) [cm]
Orientation alignment error
(mean±std) [deg]
Parking Success Rate
[%]
RS HC RS HC RS HC RS HC
Scenario 1 - 1.66±0.11 - 0.69±0.42 - 0.73±0.52 0.00 100.00
Scenario 2 3.01±0.06 2.22±0.05 3.26±0.20 0.12±0.02 2.03±0.07 0.03±0.02 100.00 100.00
Scenario 3 10.37±4.40 1.81±0.54 4.00±1.24 0.13±0.10 2.30±1.89 0.02±0.04 41.77 100.00
Scenario 4 39.26±27.18 1.26±0.20 1.56±1.73 0.13±0.05 1.07±1.19 0.09±0.06 11.48 100.00

[Fig. 4], [Fig. 5]는 앞선 100번의 주차 경로 계획으로 생성된 주차 경로 중, 경로의 길이가 가장 짧은 경로를 추종한 결과를 나타낸다. [Fig. 4]는 평행 주차 상황인 Scenario 1, [Fig. 5]는 직각 주차 상황인 Scenario 2-4에서의 추종 결과를 나타낸다. [Fig. 4], [Fig. 5]의 좌측에는, 주차 완료 시 주차 구역 대비 차량(ego-vehicle)의 위치 및 방향을 나타냈으며, 녹색선은 주차 경로, 붉은색 선은 차량의 주행 궤적을 의미한다. [Fig. 4], [Fig. 5]의 우측에는 주차 경로 추종 시, 제어기에서 계산한 조향각과 측정된 차량의 조향각 및 속도, cross-track 오차, 경로의 곡률을 주차 경로의 거리에 따라 그래프로 나타냈다. 조향 그래프에서 점선은 Kanayama 제어기에서 계산된 조향각 입력(input steering angle)을 의미하며, 실선은 측정된 차량의 조향각(measured steering angle)을 의미한다. 보라색 점선(switching)은 경로의 전후진 전환 지점을 의미한다.


[Fig. 4] 
Parallel parking results at Scenario1. In the left figures, a final alignment of the ego-vehicle, and lateral/orientation error at the target parking spot is marked. The green trajectory is a parking path by Informed RRT*. The red trajectory is a vehicle’s trajectory while tracking the parking path. In the right figures, ‘input steering angle and measured steering angle’, ‘current velocity’, cross-track error’, and ‘path curvature’ are plotted with respect to the path length. ‘input steering angle’ is a computed angle for tracking the path, by Kanayama[12] controller, and ‘measured steering angle’ is a vehicle’s steering angle while tracking. The purple vertical dashed-line represents switching


[Fig. 5] 
Perpendicular parking results at Scenario 2, 3, and 4. In the left figures, a final alignment of the ego-vehicle, and lateral/orientation error at the target parking spot is marked. The green trajectory is a parking path by Informed RRT*. The red trajectory is a vehicle’s trajectory while tracking the parking path. In the right figures, ‘input steering angle and measured steering angle’, ‘current velocity’, cross-track error’, and ‘path curvature’ are plotted with respect to the path length. ‘input steering angle’ is a computed angle for tracking the path, by Kanayama[12] controller, and ‘measured steering angle’ is a vehicle’s steering angle while tracking. The purple vertical dashed-line represents switching

3.3.1 Informed RRT*의 주차 경로 계획 결과 및 분석

[Table 3]을 보게 되면, HC를 트리 확장 방법으로 사용하여 주차 경로를 계획하는 경우, RS를 사용하였을 때 보 다 초기 경로 생성 시간(time to the first solution)이 증가하였고 경로 계획 성공률(success rate)이 낮아졌다. 이는 2가지 이유가 있다. 첫번째 이유는 RRT* 경로 계획 과정에서 샘플링된 pose가 사용되지 않는 경우가 RS를 사용하였을 때에 비하여 빈번하게 발생되기 때문이다. 두번째이유는 제한된 경로 계획 시간 동안 생성되는 랜덤 샘플 의 총 개수가 RS를 사용했을 때 보다 감소되기 때문이다.

[Table 2]를 보면, 샘플링된 pose로 트리를 확장할 때, HC를 사용한 경우 RS 보다 평균적으로 길이가 길어진 경로를 통해 트리가 확장되는 것을 알 수 있다. 길어진 경로로 확장된 트리는 도로의 너비가 좁고 장애물이 많은 주차장에서, 충돌 검사 시 충돌 가능성을 증가시키게 된다. 따라서, 랜덤 샘플이 버려지게 되며 더 많은 경로 계획 시간을 필요로 하게 된다. 또한, [Table 2]를 보면, RS에 비하여 큰 계산 속도로 인해 HC로 트리 확장 시, 더 많은 경로 계획 시간을 필요로 한다. 큰 계산 속도는 제한된 경로 계획 시간 동안, 생성되는 랜덤 샘플의 총 개수를 감소시킨다. 결과적으로 HC를 사용했을 때, 주차 경로 계획 시간이 증가되고 성공률이 감소하였다.

3.3.2 주차 경로 추종 결과 및 분석

주차 경로 추종 시, HC는 RS와 다르게, 차량이 충돌 없이 작은 위치 및 방향 오차로 주차를 완료하는 경로를 계획할 수 있다. [Table 4]를 보게 되면, HC로 생성된 주차 경로를 추종할 시, 차량은 모든 Scenario에서 100%로 주차를 성공하며, 평균 1 cm 이하의 위치 및 1 deg 이하의 방향 오차로 주차를 완료하였다. 반면에 RS로 생성한 주차 경로를 추종할 시, Scenario 2를 제외한 Scenario에서 약 40% 이하의 성공률을 가지며, 주차 성공 시에도 HC에 비하여 상대적으로 큰 위치 및 방향 오차로 주차를 완료하였다. 이 같은 차이는 [Table 3]에서 보듯이 주차 경로 상 곡률의 불연속 지점 때문에 발생한다.

전후진 전환 지점을 제외하고 곡률이 연속적인 HC의 주차 경로를 추종하면, 제어기에서 차량의 조향속도를 고려하여 조향각을 계산할 수 있게 된다. 반면에 RS를 사용한 경로를 추종할 때, 전후진 전환 지점 외에 곡률이 불연속한 지점에서, 제어기는 조향속도를 고려하지 않은 조향각을 계산하고 추종 오차가 증가된다.

[Fig. 4]에서 RS를 사용한 주차 경로를 추종할 때, 약 12.5 m 지점에서 측정된 차량의 조향각(measured steering angle, 실선)은 Kanayama 제어기에서 계산된 조향각 입력(input steering angle, 점선)을 따라가지 못하였다. 이 지점은 원호와 원호가 이어진 S자 형태의 경로로, 곡률 방향이 불연속하게(Discontinuous) 변하였기 때문이다. 결국, 차량의 조향속도를 고려하지 않고 조향각(input steering angle, 점선)이 계산되어, cross-track 오차가 크게 발생했으며 차량은 경로를 크게 벗어나며 장애물과 충돌하였다.

반면에 [Fig. 4]의 HC를 사용한 경로를 추종할 시, 측정된 차량의 조향각(measured steering angle, 실선)은 조향각 입력(input steering angle, 점선)을 따라가며 차량은 주차를 완료하였다. HC를 사용한 경로 또한, 약 11 m 지점에서 RS를 사용한 경로와 유사한 S자 형태의 경로가 나타난다. 하지만, 클로소이드 곡선이 원호와 원호의 사이를 이어주며 경로의 곡률을 연속적으로(Continuous) 변화시킨다. 이로 인해, RS의 S자 형태의 경로를 추종할 때와는 다르게, 차량의 조향속도가 고려되어 조향각 입력(input steering angle, 점선)이 계산될 수 있었고, 추종 오차가 증가하지 않으며 차량은 주차를 완료하였다.

[Fig. 5]의 Scenario 2에서 RS를 사용한 경로를 추종할 때, 주차 목표점 근처에서 주차를 완료하였음에도 곡률의 불연속 지점으로 인해 HC에 비하여 큰 위치 및 방향 오차로 주차를 완료하였다. 이는 경로의 9 m 지점에서, 원호에서 직선 경로로 곡률이 불연속하게 변하여 조향속도를 고려하지 않은 조향각이 계산되었기 때문이다. 반면에 HC를 사용한 경로를 추종할 시, 전후진 전환 지점을 제외하고 경로의 곡률이 연속적으로 변하여 상대적으로 작은 위치 및 방향 오차로 주차를 성공하였다. 주차 목표점 근처에서 차량은 원호, 클로소이드 곡선, 직선 경로 순으로 경로를 추종했다. 클로소이드 곡선에서 최대 조향속도를 고려하며 조향각이 계산되었고, 측정된 차량의 조향각(measured steering angle, 실선)과 조향각 입력(input steering angle, 점선)이 일치하게 되며, 차량은 주차를 완료하였다.

모든 Scenario에서 HC로 계획한 주차 경로는 연속적인 곡률을 갖기에, 경로의 후처리 과정이 필요하지 않았다. 또한, 차량은 전후진 전환 지점을 제외하고 정지할 필요 없이 평균 0.1 m 이하의 cross-track 오차로 경로를 추종하며, 주차를 성공할 수 있었다. HC와 같이, RS를 사용한 주차 경로를 작은 cross-track 오차로 추종하며 주차를 성공하기 위해서는 경로의 후처리 과정을 통하여 곡률의 불연속 지점을 연속적으로 만드는 방법 혹은 곡률의 불연속 지점에서 정지 후, 조향을 맞추고 주행하는 방법이 있다. 그러나, 경로의 후처리 방법은 추가적으로 계산 시간이 필요하게 된다. 더불어, 후처리 과정에서 차량의 구속 조건과 충돌 여부를 함께 고려해야하기 때문에 많은 계산 시간이 필요하다. 불연속 지점마다 정지하는 방법은 Scenario 3, 4와 같은 환경에서는 불필요하게 차량을 정지해야하는 상황이 증가한다. 위 환경에서는 주차 경로의 길이가 길어지며 곡률의 불연속 지점이 많아지게 되고, 차량이 정지해야하는 횟수가 증가되기 때문이다.


4. 결 론

본 논문에서는 RRT* 방법으로 다양한 주차장 환경에서 주차 경로 계획 시, 트리 확장 방법인 RS와 HC 조향 함수에 따른 경로 계획 성능의 차이를 비교하였다. 또한, 이를 바탕으로 HC를 사용하였을 때, RS와 다르게 충돌 없이 상대적으로 작은 위치 및 방향 오차로 주차를 완료할 수 있는 경로가 계획됨을 보였다. HC는 차량이 주차 목표점까지 장애물과의 충돌 없이 평균 2 cm 이하의 오차로 추종이 가능한 주차 경로를 계획할 수 있었다. 또한, 곡률이 연속된 경로를 계획하여, RS를 사용한 주차 경로와는 다르게 경로의 후처리 과정이 필요하지 않았으며, 차량이 평균 0.25 cm 의 위치 및 0.22 deg 이하의 방향 오차로 주차 구역에 위치하며, 주차를 성공할 수 있었다.

HC는, RS를 사용한 방법에 비하여 경로 계획 시간이 증가되는 단점이 있었다. 이에 따라, future work로는, HC 조향 함수를 트리 확장 방법으로 사용할 때, 주차 경로 계획 시간을 단축하기 위한 샘플링 방법을 고안할 계획이다. 또한, HC를 사용한 주차 경로 계획 방법을 실제 차량에 적용하여 자율주차를 구현할 것이다.


Acknowledgments

This project was funded by Phantom AI Inc., and is currently supported by the publication grant


References
1. M. Kim, G. Im, and J. Park, “A Comparative Study of Parking Path Following Methods for Autonomous Parking System,” The Journal of Korea Robotics Society, vol. 15, no. 2, pp. 147-159, Jun., 2020.
2. P. Zips, M. Böck, and A. Kugi, “Optimisation based path planning for car parking in narrow environments,” Robotics and Autonomous Systems, vol. 79, pp. 1-11, 2016.
3. S. Zhang, Y. Chen, S. Chen, and N. Zheng, “Hybrid A*-based curvature continuous path planning in complex dynamic environments,” 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 2019.
4. S. Shin, J. Ahn, and J. Park, “Desired orientation rrt (do-rrt) for autonomous vehicle in narrow cluttered spaces,” 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Daejeon, Korea (South), 2016.
5. Y. Dong, Y. Zhong, and J. Hong, “Knowledge-Biased Sampling-Based Path Planning for Automated Vehicles Parking,” IEEE Access, vol. 8, pp. 156818-156827, 2020.
6. J. A. Reeds and L.A. Shepp, “Optimal paths for a car that goes both forwards and backwards,” Pacific Journal of Mathematics, vol. 145, no. 2, pp. 367-393,1990.
7. T. Fraichard and A. Scheuer, “From Reeds and Shepp’s to continuous-curvature paths,” IEEE Transactions on Robotics, vol. 20, no. 6, pp. 1025-1035, 2004.
8. H. Banzhaf, L. Palmieri,D. Nienhüser,T. Schamm, S. Knoop, and H. M. Zöllner, “Hybrid curvature steer: A novel extend function for sampling-based nonholonomic motion planning in tight environments,” 2017 IEEE 20th International Conference on Intelligent Transportation Systems (ITSC). Yokohama, Japan, 2017.
9. A. Scheuer and T. Fraichard, “Continuous-curvature path planning for car-like vehicles,” 1997 IEEE/RSJ International Conference on Intelligent Robot and Systems. Innovative Robotics for Real-World Applications. IROS ’97, Grenoble, France, 1997.
10. A. Dosovitskiy, G. Ros, F. Codevilla, A. Lopez, and V. Koltun, “CARLA: An open urban driving simulator,” Machine Learning Research, 2017, [Online], http://proceedings.mlr.press/v78/dosovitskiy17a.html.
11. J. D. Gammell, S. S. Siddhartha, and T. D. Barfoot, “Informed RRT*: Optimal sampling-based path planning focused via direct sampling of an admissible ellipsoidal heuristic,” 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems, Chicago, IL, USA, 2014.
12. Y. Kanayama, Y. Kimura, F. Miyazaki, and T. Noguchi, “A stable tracking control method for an autonomous mobile robot,” IEEE International Conference on Robotics and Automation, Cincinnati, OH, USA, 1990.

김 민 수

2018 한양대학교 기계공학부(공학사)

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

관심분야: Autonomous Vehicle, Autonomous Valet Parking, Motion (Path) Planning

안 준 우

2016 광운대학교 로봇학부(공학사)

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

관심분야: Autonomous Vehicle, Autonomous Valet Parking, Vision-based Robot Navigation

김 민 성

2010 중앙대학교(공학사)

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

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

신 민 용

2003 서울대학교 기계 항공 공학부(공학사)

2005 Stanford University Aero/Astro(공학석사)

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

2017 현대 자동차

2017~ Phantom AI

관심분야: Automated Driving / Parking, Vehicle Control, Sensor Fusion, Trajectory Planning

박 재 흥

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

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

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

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

관심분야: Robot-Environment Interaction, Multi Contact Control, Whole Body Control, Bio-mechanics