The Korean Society Of Automotive Engineers
[ Article ]
Transactions of the Korean Society of Automotive Engineers - Vol. 30, No. 10, pp.769-784
ISSN: 1225-6382 (Print) 2234-0149 (Online)
Print publication date 01 Oct 2022
Received 17 Jan 2022 Revised 04 Jul 2022 Accepted 06 Jul 2022
DOI: https://doi.org/10.7467/KSAE.2022.30.10.769

자율주행 자동차의 스키드 조향 방법 기반 차선 변경을 위한 적응형 망각 인자를 이용하는 슬라이딩 모드 휠 속도 제어 알고리즘

김학주 ; 오광석*
한경대학교 ICT로봇기계공학부
A Sliding Mode Independent Velocity Control Algorithm Using Adaptive Forgetting Factor for Lane Change of Autonomous Vehicles Based on Skid Steer
Hakjoo Kim ; Kwangseok Oh*
School of ICT, Robotics and Mechanical Engineering, Hankyong National University, Gyeonggi 17579, Korea

Correspondence to: *E-mail: oks@hknu.ac.kr

Copyright Ⓒ 2022 KSAE / 203-01
This is an Open-Access article distributed under the terms of the Creative Commons Attribution Non-Commercial License(http://creativecommons.org/licenses/by-nc/3.0) which permits unrestricted non-commercial use, distribution, and reproduction in any medium provided the original work is properly cited.

Abstract

This paper proposes sliding mode velocity control using adaptive forgetting factor for lane change based on the skid-steer of an autonomous vehicle. The driving path was designed by using the 3rd polynomial function with virtual preview point and vehicle relative position. For the skid steer method-based lane change, the desired wheel velocity was computed by kinematic analysis. The error dynamics was designed based on wheel dynamics to come up with an adaptive controller. The time-varying parameters that contain uncertainties in error dynamics were estimated using recursive least squares with adaptive forgetting factor. Using the gradient descent method, the forgetting factor was adjusted with upper and lower limitation values. The control input that satisfies the Lyapunov stability condition was derived using the error dynamics. The proposed control algorithm was constructed in Matlab/Simulink with CarMaker. The lane change scenario was applied to verify the reasonable performance of the proposed control algorithm.

Keywords:

Lane change, Skid steer, Sliding mode control, Recursive least squares, Adaptive forgetting factor, Gradient descent method

키워드:

차선 변경, 스키드 조향, 슬라이딩 모드 제어, 재귀 최소 자승법, 적응형 망각 인자, 경사 하강법

1. 서 론

차량의 안전성과 편리성을 확보하기 위하여 최근 자율주행의 핵심 기술로써 인지, 판단, 제어 분야의 다양한 연구들이 진행되고 있다. 그리고 자동차의 높은 거동 및 제어 자유도를 위하여 구동 및 조향 모터를 이용하는 SBW(Steer By Wire) 시스템 상용화를 위한 연구들 또한 활발히 진행되고 있다. 자율주행 기술과 SBW 시스템 기반 종/횡방향 제어를 위한 다양한 제어 이론이 융합적으로 연구 및 개발되고 있다. 그리고 센서와 구동 모터의 신호적 결함 및 하드웨어 고장이 발생 되는 경우 주행 안전을 확보하기 위해 여러 산업체 및 연구 기관에서는 고장 탐지 및 허용 제어 등의 연구들이 진행되고 있다.

Wang 등1)은 인휠 모터를 이용하는 전기 자동차의 조향 시스템 성능 저하 및 신호 고정으로 발생될 수 있는 고장을 보상하기 위한 H-infinite과 강건 적응 방법론들을 이용해 고장 허용 제어기를 설계하였다. Chen 등2)은 전기 자율주행 자동차의 조향 시스템에 발생된 고장 신호를 추정하고, 차량의 슬립 각도를 고려하는 고장 허용 경로 추종 제어 알고리즘을 제안하였다. Zhao 등3)은 T-S 퍼지 모델을 이용하여 차량 횡방향 동역학 모델을 근사화하였으며, 자율주행 자동차의 액츄에이터의 고장을 보상하기 위해 고장 허용 제어 전략을 제안하였다. 나원빈 등4)은 모델 기반 조향각 제어 입력과 센서값의 오차를 이용한 임계값 기반 고장 진단기를 설계하였으며, 고장 신호에 대한 민감도를 분석하였다. Wang 등,1) Chen 등,2) Zhao 등,3) 나원빈 등4)에서는 조향 시스템의 성능 저하, 신호 고정 등, 다양한 원인으로 발생할 수 있는 고장을 보상하기 위하여 고장 탐지 및 허용 제어 전략들을 확인할 수 있었다.

Wang과 Wang5)은 타이어 노면 마찰 계수 정보가 필요하지 않은 인휠 모터와 모터 드라이버의 고장 진단 방법과 제어 할당 기반 허용 제어 알고리즘을 제안하였다. 전남철과 이형철6)은 전기 자동차 인휠 모터의 전류, 위치 센서를 위한 차량 동역학 및 모터 시스템이 고려된 통합 고장 진단 알고리즘을 제안하였다. Zhang 등7)은 인휠 모터의 성능 저하로 인한 고장을 보상하기 위하여 고장 탐지 및 허용 제어 방법론을 제안하였다. Zhang 등8)은 인휠 모터 고장을 보상하기 위한 운전자 특성이 고려된 고장 탐지 및 슬라이딩 모드 제어와 게임 이론 기반 허용 제어 방법론을 제안하였다. Wang과 Wang,5) 전남철과 이형철,6) Zhang 등,7) Zhang 등8)에서는 인휠 모터의 성능 저하, 다양한 센서 고장을 보상하기 위하여 다양한 고장 탐지 및 허용 제어 전략들이 사용되었음을 확인할 수 있었다.

Deng 등9)은 SBW 시스템을 이용하는 전기 자동차의 거동 제어를 위하여 적응형 재귀 슬라이딩 모드 제어 알고리즘을 제안하였다. Hu 등10)은 4륜 독립 구동 자율주행 자동차의 차선 유지를 위하여 적응형 슬라이딩 모드 알고리즘 기반 보조 조향 장치 제어를 수행하였다. Zou와 Zhao11)는 SBW 시스템의 안전성을 위하여 이중 모터를 이용하였으며 H-infinite를 이용하여 인가되는 센서 잡음에 대하여 강건한 제어를 수행하였다. Deng 등,9) Hu 등,10) Zou와 Zhao11)에서는 SBW 시스템 및 보조 조향 장치의 제어를 위한 제어 이론을 확인할 수 있었다.

김태완 등12)은 스키드 스티어 차량의 경로 추적 제어를 위하여 모델 예측기와 모델 학습에 이용되는 가우시안 과정을 적용하였다. Reina와 Galati13)는 스키드 스티어 차량을 이용하여 실시간으로 직접 계측하기 어려운 물리량 및 지형 추정 방법을 제안하였다. 김태완 등,12) Reina와 Galati13)에서는 스키드 조향 차량을 이용한 다양한 연구를 확인할 수 있었다.

본 연구에서는 자율주행 자동차의 조향 장치 고장 발생 시 인휠 모터 기반 스키드 조향 방법을 이용한 비상 조향 방법을 제안한다. 이를 위해 인휠 모터 기반 독립 구동 시스템을 이용하는 자율주행 자동차의 스키드 조향 기반 차선 변경 알고리즘을 제안한다. 차선 변경을 위한 주행 경로는 가상으로 결정된 예견 지점과 차량의 상대 위치를 이용하여 3차 다항식으로 설계되었다. 차선 변경을 위해 설계된 주행 경로의 회전 반경과 차량의 기구학적 분석을 통해 개별 요구 휠 속도를 도출 및 적용되었다.

스키드 조향은 전륜 및 후륜 조향 시스템을 이용하지 않고, 좌우 휠 토크 차등 분배를 통하여 차량의 선회 거동을 가능하게 한다. 일반적으로 애커먼 조향을 이용하는 차량 대비 스키드 조향을 이용하는 차량은 제자리 회전 등의 주행이 가능한 상대적 장점이 있다. 고장 안전 관점에서 4륜 독립 구동이 가능한 차량이 직진 주행 중 조향부의 고장이 탐지되었다는 가정하에 주행 안전을 확보할 수 있는 차선 변경 알고리즘이 개발 및 평가되었다.

적응 제어는 시스템 노후화 및 시스템에 인가되는 외란 및 불확실성을 극복할 수 있는 방법론으로 변수 추정 적응 제어와 학습 기반 적응 제어 등이 있다. 본 연구에서는 변수 추정 적응 제어를 이용하는 모델 자유 적응 제어 방법론으로 적응형 망각 인자 기반 슬라이딩 모드 제어 알고리즘이 제안되었다. 단순 오차 동역학 모델의 외란과 불확실성을 내포하는 집중화된 파라미터들을 추정하기 위하여 망각 인자 기반 재귀 최소 자승법이 적용되었다.

집중화된 파라미터들을 재귀 최소 자승법으로 추정 시 적절한 망각 인자 값이 결정되지 않을 경우, 과도한 채터링 현상 및 제어 안정성을 잃을 수 있는 한계점이 존재한다. 따라서 본 연구에서는 제어 오차를 줄이고 적절한 망각 인자를 도출하기 위하여 오차 변화율과 망각 인자 변화율 간의 관계 함수가 설계되었다. 설계된 관계 함수 기반 추정된 계수 경사 하강법에 반영되어 적응형 망각 인자를 갱신한다. 적응형 망각 인자와 재귀 최소 자승법으로 추정된 오차 동역학 모델의 집중화된 파라미터들은 랴푸노프 기반 설계된 비용함수에 반영되어 안정성 조건을 만족하는 휠 토크 제어 입력이 도출되었다. 제안된 자율주행 자동차의 스키드 조향 기반 차선 변경을 위한 적응형 휠 속도 제어 알고리즘은 상용 소프트웨어 CarMaker와 Matlab/Simulink를 이용하여 시뮬레이션 기반 성능평가가 수행되었다. 성능평가 결과 제안된 알고리즘은 합리적인 차선 변경 제어 성능을 보여주었다.

본 논문의 구성은 다음과 같다. 2장에서는 스키드 조향 기반 차선 변경 알고리즘, 3장에서는 차선 변경 시나리오 기반 성능평가 결과를 기술하며, 4장은 본연구의 결론, 한계점 분석과 향후 계획을 기술한다.


2. 스키드 조향 기반 차선 변경 알고리즘

2.1 차선 변경을 위한 목표 휠 속도 결정 방법

Fig. 1은 스키드 조향 기반 차선 변경 알고리즘의 모델 개략도이다. Fig. 1에서 j는 각 휠의 위치로 j=(fl, fr, rl, rr)와 같이 나타낼 수 있다. 차선 변경을 위하여 3차 다항식 기반 주행 경로를 도출하였으며, 도출된 주행 경로의 회전 반경과 차량의 역학적 분석으로 스키드 스티어 기반 요구 속도를 차등으로 분배하였다. 분배된 요구 속도를 추종하기 위하여 설계된 적응형 망각 인자를 이용하는 슬라이딩 모드 제어 알고리즘을 보여준다. Fig. 2는 차선 변경을 위한 3차 다항식 기반 주행 경로를 보여준다.

Fig. 1

Model schematics of skid steer based lane change algorithm

Fig. 2

3rd polynomial function based on path planning

차량의 위치 (xt, yt), 차량의 요 각도 ψt, 가상 예견 지점의 좌표 (xp, yp)와 기울기 ψp를 이용하는 차선 변경을 위한 3차 다항식 기반 자율주행 경로 설계 함수는 식 (1)과 같다.

abcd=xt3xt2xt1xp3xp2xp13xt22xtxt03xp22xpxp0-1ytyptanψttanψp(1) 

식 (1)에서 가상 예견 지점 좌표(xp, yp)는 가상 예견 지점의 거리 Lp를 이용하여 (Lp+xt, yp)로 정의될 수 있으며, Lp는 차량의 종방향 속도 υx와 예견 시간 tg을 이용하여 설계되었다. yp는 요구 가상 예견 지점 좌표 yp,desyt를 이용하여 식 (2)와 같이 설계되었다. 차량이 주행 중 발생하는 오버슛, 정상 상태 오차를 최소화하기 위하여 미분 항, 미분 계수 kd, 적분 항과 적분 계수 ki가 포함되어 식 (2)식 (3)으로 재도출될 수 있다.

yp=yp.des-yt(2) 
eyp=yp+kiypdt+kddypdt(3) 

식 (1)에서 3차 다항식의 기울기를 나타내는 a, b, c, d와 차량의 횡방향 속도 y˙t와 횡방향 가속도 y¨t를 이용하여 주행 경로의 곡률 κ가 도출될 수 있으며 이는 식 (6)과 같다.

yt'=3axt2+2bxt+c(4) 
yt''=6axt+2b(5) 
κ=yt''1+yt'23(6) 

식 (6)에서 도출된 곡률을 이용하는 순간 회전 중심 반경은 식 (7)과 같다.

R=1/κ(7) 

Fig. 3식 (7)의 순간 회전 중심 반경이 포함된 기구학적 분석으로 스키드 스티어 방법 기반 차선 변경을 위한 요구 휠 속도를 보여준다.

Fig. 3

Kinematic analysis of skid steer method

차량의 종방향 요구 속도를 전륜 휠들의 중심과 동일한 x 좌표 위치를 가정하고, 차량의 전폭 tw과 순간 회전 중심 반경을 이용하여 스키드 조향 기반 분배된 요구 휠 속도는 식 (8)과 같다.

υdes,fl=2R-tw2Rυdes,υdes,rl=υdes,flυdes,fr=2R+tw2Rυdes,υdes,rr=υdes,fr(8) 

2.2 적응형 망각 인자를 이용하는 슬라이딩 모드 제어 알고리즘

Fig. 4는 본 연구에서 제안하는 적응형 망각 인자를 이용하는 재귀 최소 자승법 기반 슬라이딩 모드 제어 알고리즘의 모델 개략도이다. 제안된 제어기 설계를 위해 요구 휠 속도와 휠 속도로 정의된 오차 상태량, 휠의 수학적 모델을 이용하여 오차 동역학 모델이 도출되었다. 도출된 오차 동역학 모델은 적응형 망각 인자를 이용하는 재귀 최소 자승법에 반영되어 입력 계수 및 외란 항이 추정되었다. 오차 상태량에 따른 적절한 망각 인자를 결정하기 위하여 오차 상태량의 변화율과 망각 인자 변화율의 관계를 나타내는 가상 함수가 설계되었다. 설계된 가상 함수는 경사 하강법에 반영되어 적응형 망각 인자 규칙이 설계되었다. 추정된 오차 동역학 모델은 랴푸노프 방법 기반 비용함수에 반영되어 랴푸노프 유한 시간 안정성 조건을 만족하는 제어 입력이 도출되었다. Fig. 5는 휠 동역학 모델과 차량이 주행 중 발생 되는 휠 슬립 각도를 보여준다.

Fig. 4

Model schematics of proposed control algorithm

Fig. 5

Wheel dynamics and wheel slip angle

수학적 모델 기반 휠의 운동 방정식과 휠의 슬립 비율은 각각 식 (9), (10)과 같이 정의될 수 있다.

ω˙=1JT-bω-rFx-frFz(9) 
s=rω-υcosαwrω(10) 

요구 휠 속도와 휠 속도를 이용하여 정의된 오차 상태량은 식 (11)과 같다.

e=υdes-υ(11) 

식 (9), (10), (11)를 이용하여 도출된 오차 동역학 모델은 식 (12)와 같으며, 식 (12)에서 집중화된 입력 계수 Meq, 외란 항 Neq가 정의되었으며 이는 각각 식 (13), (14)와 같다.

e˙=-r1-scosαwJT+υ˙des+r1-scosαwJbω+rFx+fFz(12) 
Meq=-r1-scosαwJ(13) 
Neq=υ˙des+r1-scosαwJbω+rFx+fFz(14) 

식 (12), (13), (14)를 이용하여 오차 동역학 모델은 아래와 같이 정리될 수 있다.

e˙=MeqT+Neq(15) 

식 (15)의 정리된 오차 동역학 모델에서 불확실성과 외란을 내포하는 MeqNeq를 추정하기 위하여 다중 망각 인자를 이용하는 재귀 최소 자승법이 적용되었으며, 이는 Vahidi 등14)을 참고하였다. 추정을 위한 1차 근사 식은 식 (16)과 같으며, 출력 인자, 회귀 인자, 추정값은 각각 식 (17), (18), (19)와 같다.

y=ϕTθ(16) 
y=e˙(17) 
ϕ=T  1(18) 
θ =Meq   NeqT(19) 

식 (13), (14), (15), (19)에서 추정값 θ는 집중화된 파라미터 Meq, Neq는 시불변 하는 차량의 파라미터들, 시변하는 상태량들이 포함되었다. 물리적 특성이 반영된 차량 파라미터 및 상태량들을 실시간으로 추정하여 제어 오차를 줄이기 위하여 Meq, Neq가 추정되었다. 다중 망각 인자 λ(0 < λ < 1)를 가지는 재귀 최소 자승법의 목적함수는 식 (20)과 같다.

Vθ^1k,θ^2k,k=12i=1kλ1k-iyi-ϕ1iθ^1k-ϕ2iθ2i   2+12i=1kλ2k-iyi-ϕ1iθ1i-ϕ2iθ^2k   2(20) 

실시간 추정을 위한 재귀적 형태의 식 θ^ 추정값 갱신을 위한 L과 공분산 행렬 계산을 위한 P는 각각 식 (21), (22), (23)과 같다.

θ^1kθ^2k=1L1kϕ2kL2kϕ1k1-1×θ^1k-1+L1kyk-ϕ1kθ^1k-1θ^2k-1+L2kyk-ϕ2kθ^2k-1   (21) 
L1kL2k=P1k-1ϕ1k/λ1+ϕ1TP1k-1ϕ1kP2k-1ϕ2k/λ2+ϕ2TP2k-1ϕ2k   (22) 
P1kP2k=1-L1kϕ1TkP1k-1/λ11-L2kϕ2TkP2k-1/λ2(23) 

재귀 최소 자승법에 이용된 망각 인자 λ는 결정된 망각 인자의 값에 따라 추정값에 미치는 영향력을 결정할 수 있다. 망각 인자가 1에 가까운 값을 가지는 경우 이전 데이터를 기억하도록 정의되었다. 오차 상태량에 따른 망각 인자를 결정하기 위하여 정의된 가상 함수는 식 (24)와 같다.

e˙=C^λ˙(24) 

식 (24)에서 민감도를 나타내는 비례 상수 C는 단일 고정 망각 인자를 이용하는 재귀 최소 자승법으로 추정되었으며, 식 (24)를 이용하는 경사 하강법 기반 적응형 망각 인자를 도출하는 과정은 아래와 같다.

λ˙=-γek=-γeC^(25) 
λ=0t-γeC^dt(26) 

랴푸노프 방법 기반 두 가지 수렴 조건을 포함하여 설계된 비용함수는 각각 식 (27), (28), (29)와 같다.

J=12e2(27) 
Condition 1 :J˙0,e0(28) 
Condition 2 :limeJ=(29) 

식 (15), (27), (28)을 이용하여 랴푸노프 수렴 조건식은 아래와 같이 정리될 수 있다.

J˙=eM^eqTw+N^eq0(30) 

식 (30)에서 추정된 외란 항 N^eq는 외란 경계 영역 조건 L^b를 이용하여 N^eqL^b로 정의될 수 있으며, 주입항의 크기 ρ와 함께 제어 입력은 u=-ρsign(e)로 정의될 수 있다. 식 (13), (14), (30)을 이용하여 재도출된 수렴 조건식은 아래와 같다.

J˙=eM^eqTw+Neq-eρ-L^b(31) 

랴푸노프 유한 시간 수렴 조건을 만족하는 제어 입력을 도출하기 위해 수렴 이득 값 α식 (27), (28)을 이용하여 식 (32)로 재도출 될 수 있다.

J˙-αJ1/2(32) 

설계된 유한 시간 수렴 조건식, 식 (32)를 고정 이산 시간 τ와 함께 0 ≤ τt로 적분하여 유한 수렴 시간 tr을 도출하는 과정은 아래와 같다.

J1/2t-12αt+J1/20(33) 
tr2J1/20α(34) 

랴푸노프 안정성 조건식인 식 (30), (32)를 이용하여 주입항의 크기 ρ를 도출하는 과정은 아래와 같다.

J˙=-eρ-L^b-α2e(35) 
ρ=L^b+α2(36) 

식 (31)에서 M^eqTwu=-ρsign(e)를 등가 입력으로 가정하여 도출되는 휠 토크 입력은 식 (37)과 같다.

Tw=-1M^eqL^b+α2signe(37) 

식 (37)에 도출된 휠 토크 제어 입력의 부호 함수의 영향으로 발생할 수 있는 채터링 현상을 최소화하기 위하여 시상수인 τc과 전달 함수를 이용한 등가 휠 토크 제어 입력은 식 (38)과 같다.

Te=1τcs+1Tw(38) 

다음 장에서는 자율주행 자동차의 스키드 조향 기반 차선 변경을 위한 적응형 속도 제어 알고리즘의 성능평가 결과를 기술한다.


3. 성능평가

Fig. 6은 성능평가를 위해 제안된 스키드 조향 기반 차선 변경을 위한 적응형 망각 인자를 이용하는 슬라이딩 모드 휠 속도 제어 알고리즘의 모델 개략도를 보여준다. 제안된 제어 알고리즘은 CarMaker와 연동되어 Matlab/Simulink 상에서 구성되었다. 본 연구에서는 제안된 제어 알고리즘의 성능평가를 위하여 차선 변경 시나리오가 적용되었다. 차선 변경을 위해 성능평가 중 yp,des를 0 m에서 -3.5 m로 변경하였으며, 합리적 yp 도출을 위하여, 시상수 τp 기반 일차 전달 함수가 적용되었다.

Fig. 6

Model schematics of performance evaluation

성능평가를 위하여 차량의 속도가 10 kph로 주행하는 경우를 Case [1], 30 kph로 주행하는 경우를 Case [2]로 구분하였다. 세부적으로 파라미터의 불확실성을 고려하지 않은 슬라이딩 모드 제어기(SMC)가 적용된 경우를 Case [1-1], 고정 망각 인자를 이용하는 슬라이딩 모드 제어기(CFSMC, Constant Forgetting Sliding Mode Control)가 적용된 경우를 Case [1-2], 적응형 망각 인자를 이용하는 슬라이딩 모드 제어기(AFSMC, Adaptive Forgetting Sliding Mode Control)가 적용된 경우를 Case [1-3]로 구분하였다. 그리고 AFSMC의 채터링 현상 분석을 위하여, 시뮬레이션 이산 시간이 0.1 ms로 결정되고 AFSMC가 적용된 경우를 Case [1-4]로 구분하였다. Case [1-1], Case [1-2], Case [1-3]의 이산 시간은 1 ms로 결정되었다. Case [2-1], [2-2], [2-3], [2-4] 또한 파라미터의 불확실성 고려, 적응형 망각 인자의 적용 유/무 및 이산 시간 결정에 따라 구분되었다. Table 1은 성능평가를 위하여 이용된 차량의 제원을 보여준다. 구분된 Case들의 구체적인 내용은 Table 2에서 볼 수 있으며, Table 3은 Case [1]의 제어 파라미터들을 보여준다.

Vehicle parameters for performance evaluation

Performance evaluation scenario

Performance evaluation control parameters, case [1]

Fig. 7부터 Fig. 20은 Case [1]에 대한 성능평가 결과들을 보여준다. Fig. 7은 10 kph로 주행하는 차량이 10 sec에서 차선 변경을 위해 분배된 스키드 조향 기반 요구 속도를 확인할 수 있다. FL은 전륜 좌측 휠, FR은 전륜 우측 휠, RL은 후륜 좌측 휠, RR은 후륜 우측 휠을 의미한다. Fig. 7에서 볼 수 있듯이 Case [1-2], [1-3], [1-4]에서 약 10 sec에서 오버슛 현상이 발생되었으나 모든 Case [1]에서 도출된 요구 휠 속도를 합리적으로 추종함을 확인할 수 있었다. Fig. 8은 속도 오차 상태량 그래프를 나타낸다. Case [1-1], [1-2], [1-3], [1-4] 모두 차선 변경 구간에서 상대적 큰 값의 오차 상태량을 나타내었으며, Case [1-3], [1-4]는 Case [1-1], [1-2]에 비해 상대적 채터링 현상이 완화된 것을 확인할 수 있었다.

Fig. 7

Wheel velocity (case [1])

Fig. 8

Velocity error (case [1])

그리고 Case [1-4]는 Case [1-3]보다 10 sec구간에서 오차 상태량이 튀는 현상이 상대적 작은 것을 확인할 수 있었다. Table 4는 Case [1]의 오차 평균값과 표준편차를 보여준다.

Analysis of error distribution (case [1])

Table 4에서 확인할 수 있듯이 Case [1-1]의 RR이 가장 작은 평균값, Case [1-4]의 RL이 가장 큰 평균값을 나타내었다. Case [1-4]의 FR, RR이 가장 작은 표준편차, Case [1-1]의 RL이 가장 큰 표준편차를 나타내었다. Fig. 9는 오차 변화율과 망각 인자 변화율의 관계를 나타내는 비례 상수 C를 보여준다. Case [1-3]의 추정된 비례 상수는 약 -100~100 사이의 값을 나타내었으며, Case [1-4]의 -500~500 사이의 값을 나타내었다. Fig. 10Meq, Neq를 추정하기 위하여 결정된 망각 인자를 보여준다. 여기서 비례 상수 C가 반영된 적응형 망각 인자는 Case [1-3], [1-4]에서 볼 수 있다.

Fig. 9

Estimated sensitivity gain (case [1])

Fig. 10

Forgetting factor (case [1])

CFSMC를 이용하는 Case [1-2]의 경우, Table 2에서 확인할 수 있듯이 망각 인자 λ는 0.999로 결정되었다. Case [1-3]의 망각 인자는 FL과 RL이 서로 유사한 값을 가졌으며, FR과 RR이 서로 유사한 값을 가지는 것을 볼 수 있다. Case [1-4]의 망각 인자는 FL, FR이 서로 유사한 값을 가졌으며, RL과 RR이 서로 유사한 값을 가지는 것을 볼 수 있었다. 그리고 차선 변경이 시작되는 시점 10 sec에서 망각 인자의 개형이 변하는 것을 확인할 수 있었다.

Fig. 11은 집중화된 입력 계수 Meq를 보여준다. SMC를 이용하는 Case [1-1]의 경우, 그래프와 Table 2에서 볼 수 있듯이 0.01로 결정되었으며, CFSMC를 이용하는 case [1-2], AFSMC를 이용하는 Case [1-3], [1-4]는 각각 고정, 적응형 망각 인자를 이용하는 재귀 최소 자승법으로 추정된 값들을 보여준다. Fig. 12는 외란 항 Neq를 보여주며, Case [1-1]의 경우, 5로 결정되었으며, Case [1-2], case [1-3], [1-4]의 경우, 고정, 적응형 망각 인자를 이용하는 재귀 최소 자승법으로 추정된 값들을 보여준다.

Fig. 11

Input coefficients (case [1])

Fig. 12

Disturbance terms (case [1])

Fig. 13은 휠 토크 입력을 보여준다. 10~40 sec에서 차선 변경을 위하여 제어 입력의 개형이 변화하는 것을 볼 수 있다. Fig. 14는 휠 토크 입력의 주파수 분석을 보여주는 그래프로 Case [1-1], [1-2], [1-3]에서 130~150 Hz 영역에서 제어 입력이 인가되었으며, Case [1-4]는 165~200 Hz 영역에서 제어 입력이 인가되는 것을 확인할 수 있었다. 그리고 Case [1-1]의 주파수의 크기가 가장 큰 것을 확인할 수 있었다. Fig. 15는 차량의 주행 경로를 보여준다. Fig. 15에서 볼 수 있듯이 약 80 m부터 180 m에서 차선 변경이 수행되었다.

Fig. 13

Wheel torque control input (case [1])

Fig. 14

Frequency analysis : Fourier transform (case [1])

Fig. 15

Trajectory (case [1])

Case [1-3]은 약 135 m에서 -3.76 m, case [1-4]는 약 -3.78 m 정도의 오버슛 현상을 확인할 수 있었으며, Case [1-1], [1-2]는 약 3.8 m 정도의 오버슛 현상을 확인할 수 있었다. Case [1-3]의 경우, 상대적 오버슛 현상이 작은 값을 가지는 것을 볼 수 있었다.

Fig. 15부터 Fig. 20은 차량 상태량의 그래프를 보여준다. Figs. 16, 17은 각각 종방향, 횡방향 속도를 보여주며 Case [1-4]의 경우, Case [1-1], [1-2], [1-3] 대비 상대적 채터링 현상이 완화된 것을 확인할 수 있었다. Figs. 18, 19는 각각 종방향 가속도와 횡방향 가속도를 보여주며, Case [1-4]에서 채터링 현상이 가장 완화된 것을 볼 수 있었다. Fig. 20, 요 변화율의 그래프를 보여준다. 채터링 현상이 가장 큰 것을 확인할 수 있었다. 그래프에서 볼 수 있듯이 SMC가 적용된 Case [1-1]에서의 Case [1] 성능평가 결과, 제안된 AFSMC의 합리적인 제어 성능을 확인할 수 있었다. Case [1]의 성능평가 그래프에서 SMC, CFSMC 대비 AFSMC에서 채터링 현상이 완화된 것을 볼 수 있었다. 그리고 Case [1-3], [1-4]의 이산 시간 결정에 따라 채터링 현상이 달라지는 것을 확인할 수 있었다. 상대적 연산 주기가 짧고 시정수가 작은 값이 결정된 Case [1-4]는 상대적 시정수가 큰 값으로 결정된 Case [1-3]보다 채터링 현상이 상대적 완화된 것을 볼 수 있었다. 그러나 Case [1-4]에서도 채터링 현상이 존재하고 있음을 확인할 수 있었다. 따라서 더욱 고도화된 적응형 슬라이딩 모드 제어 알고리즘 개발을 위하여, 향후 채터링 완화 기법을 개발을 계획하고 있다.

Fig. 16

Longitudinal velocity (case [1])

Fig. 17

Lateral velocity (case [1])

Fig. 18

Longitudinal acceleration (case [1])

Fig. 19

Lateral acceleration (case [1])

Fig. 20

Yaw rate (case [1])

Table 5는 Case [2]에 이용된 제어 파라미터들을 보여준다. Fig. 21부터 Fig. 34는 Case [2]에 대한 성능평가 결과들을 보여준다. Fig. 21에서 30 kph로 주행 중인 차량이 차선 변경을 위해 분배된 요구 휠 속도 합리적으로 추종함을 확인할 수 있었다. Fig. 22는 휠 속도 오차 상태량을 보여준다. 그래프에서 볼 수 있듯이 AFSMC가 적용된 Case [2-4]가 채터링 현상이 가장 완화된 것을 확인할 수 있었다. Table 6은 Case [2]의 오차 평균값과 표준편차를 보여준다.

Performance evaluation control parameters, case [2]

Fig. 21

Wheel velocity (case [2])

Fig. 22

Velocity error (case [2])

Analysis of error distribution (case [2])

Table 6에서 볼 수 있듯이 Case [2-4]의 RR이 가장 작은 평균값, Case [2-2]의 RR이 가장 큰 평균값을 나타내었다. Case [2-4]의 RR이 가장 작은 표준편차, Case [2-1]의 RR이 가장 큰 표준편차를 나타내었다. Fig. 23은 추정된 비례 상수 C를 보여주며, Fig. 24는 적응형 망각 인자를 보여준다. Fig. 24에서 볼 수 있듯이 Case [2-3]의 적응형 망각 인자는 1에 가까운 값으로 갱신되었다. 그리고 Case [2-4]에서 RR은 0.55와 가까운 값으로 갱신되었으며, FL, FR, RL은 1에 가까운 값으로 갱신되었다. Case [2-3], [2-4] 모두 상대적 큰 변화 없이 특정 값으로 갱신되는 것을 확인할 수 있었다. Fig. 25는 집중화된 입력 계수 Meq를 보여준다. SMC를 이용하는 Case [2-1]의 경우, Table 2에서 확인할 수 있듯이 0.055로 결정되었으며, CFSMC를 이용하는 Case [2-2]와 AFSMC를 이용하는 Case [2-3], [2-4]는 추정된 Meq를 보여준다.

Fig. 23

Estimated sensitivity gain (case [2])

Fig. 24

Adaptive forgetting factor (case [2])

Fig. 25

Estimated input coefficients (case [2])

Fig. 26은 외란 항 Neq를 보여주며, Case [2-1]의 경우, Table 5에서 볼 수 있듯이 5로 결정되었으며, Case [2-2], case [2-3], [2-4]의 경우, 각각 고정 및 적응형 망각 인자를 이용하는 재귀 최소 자승법으로 추정된 값들을 보여준다. 그래프에서 볼 수 있듯이 차선 변경 완료 이후 집중화된 파라미터 Meq, Neq의 추정된 값이 지속적으로 커지는 것을 확인할 수 있었다. 상대적 작은 값과 작은 변화율 기반 갱신되는 것을 확인할 수 있었지만, 추정 절대적 안정성 확보를 위한 Directional forgetting을 이용하는 재귀 최소 자승법 적용을 계획하고 있다.

Fig. 26

Estimated disturbance terms (case [2])

Fig. 27은 휠 토크 제어 입력 그래프를 보여주며, Fig. 28은 휠 토크 제어 입력의 주파수 분석을 보여준다. Case [2-1], [2-2], [2-3]의 경우 80~90 Hz 영역에서 제어 입력이 지배적으로 인가된 특성을 확인할 수 있었으며, Case [2-4]의 경우, 121~130 Hz에서 제어 입력이 지배적으로 인가된 특성을 확인할 수 있었다. 이러한 특성은 Matlab/Simulink 및 CarMaker의 이산 시간이 각각 1 ms, 0.1 ms로 적용되었기 때문에 가능한 것으로 확인되었으며 향후 실 시스템의 물리적 제약 조건이 고려된 슬라이딩 모드 제어 알고리즘 고도화를 계획하고 있다.

Fig. 27

Wheel torque control input (case [2])

Fig. 28

Frequency analysis : Fourier transform (case [2])

Fig. 29는 차량의 주행 경로를 보여주며 약 350 m~550 m까지 차선 변경이 수행됨을 볼 수 있다. Fig. 30부터 Fig. 34는 차량의 물리량을 보여주는 그래프이다. Figs. 30, 31은 각각 종방향 및 횡방향 속도의 그래프이며, Figs. 32, 33은 각각 종방향 가속도와 횡방향 가속도를 보여주며, Fig. 34는 요 변화율을 보여준다. 차량의 물리량을 나타내는 그래프에서 볼 수 있듯이 Case [2-4]에서 채터링 현상이 상대적 가장 완화된 것을 확인할 수 있었다.

Fig. 29

Trajectory (case [2])

Fig. 30

Longitudinal velocity (case [2])

Fig. 31

Lateral velocity (case [2])

Fig. 32

Longitudinal acceleration (case [2])

Fig. 33

Lateral acceleration (case [2])

Fig. 34

Yaw rate (case [2])

Case [2]의 경우, 휠 속도가 상대적으로 Case [1]에 비하여 과도 구간에서의 오버슛 현상은 작은 것을 확인할 수 있었다. 그러나 진동수 관점에서 Case [1]에 비하여 상대적 큰 값을 나타내었으며, 이러한 경향은 대상 차량의 동적 거동 등에서 나타내는 진동수 해석 결과(Fig. 28)에서 확인할 수 있다. 성능평가 결과, 주행 경로를 보여주는 Figs. 15, 29에서는 차선 변경 경로에 대한 오버슛 현상을 확인할 수 있었다. 다음 장에서는 본 연구의 결론, 한계점 분석 및 향후 계획을 기술한다.


4. 결 론

본 연구에서는 자율주행 자동차의 스키드 조향 기반 차선 변경을 위한 적응형 망각 인자를 이용하는 슬라이딩 모드 제어 알고리즘을 제안하였다. 스키드 조향 기반 차선 변경을 위하여 가상 예견 지점을 이용하여 3차 다항식 기반 주행 경로가 설계되었으며, 설계된 주행 경로의 곡률을 이용해 회전 반경과 차량의 기구학적 분석 기반 요구 휠 속도가 도출되었다.15) 분배된 요구 속도를 추종하기 위하여 휠의 동적 방정식이 반영된 오차 동역학 모델의 불확실성과 외란을 포함하는 집중화된 파라미터들은 망각 인자 기반 재귀 최소 자승법을 이용하여 추정하였다. 제어 오차를 줄이기 위하여 오차 변화율과 망각 인자 변화율의 관계를 나타내는 비례 상수와 함께 가상 관계 함수를 설계하였다. 설계된 가상 관계 함수는 경사 하강법에 반영되어 적응형 망각 인자를 도출하였다. 추정된 오차 동역학 모델은 랴푸노프 기반 비용함수에 반영되어 안정성 조건을 만족하는 휠 토크 제어 입력이 도출되었다. 제안된 제어 알고리즘의 성능평가를 위해 속도, 파라미터 불확실성 고려 여부, 적응형 망각 인자 적용 여부 및 이산 시간 결정에 따라 Case가 구분되었으며, 차선 변경 시나리오가 적용되었다. 제안된 알고리즘은 Matlab/Simulink와 상에 구성되었으며, CarMaker와 연동되어 합리적인 제어 성능평가 결과를 확인할 수 있었다. 그러나 차량이 차선 변경 중 주행 경로와 휠 속도에서 오버슛 현상이 발생 됨을 확인할 수 있었다. 그리고 채터링 현상 관점에서 AFSMC가 적용된 경우, SMC, CFSMC보다 상대적 채터링 현상이 완화된 것을 볼 수 있었지만, 채터링 현상이 존재하고 있음을 확인할 수 있었다. 그리고 성능평가 이전 적응 이득 값 및 수렴 이득 값의 조정이 필요한 한계점을 확인할 수 있었다. 따라서 향후 차선 변경 시 오버 슛을 줄이기 위한 경로 결정 방법론과 현실적인 휠 토크 제어 입력 도출을 위한 채터링 완화 기법 연구를 계획하고 있다. 더불어 적응 이득 갑의 자동 결정 방법론 연구 또한 향후 계획으로 고려하고 있으며 불확실성을 내포하고 있는 추정값들의 추정 안정성 확보를 위해 Directional forgetting 기반 재귀 최소 자승법 적용을 계획하고 있다. 본 연구에서 제안한 스키드 조향 기반 차선 변경을 위한 적응형 망각 인자를 이용하는 제어 알고리즘은 향후 자율주행 자동차의 고장 안전을 포함하는 다양한 제어 기법으로 사용될 것으로 기대한다.

Nomenclature

T : torque, Nm
I : inertia, kgm2
b : damping, Nms/rad
fr : rolling resistance, [-]
r : wheel radius, m
ω : angular velocity, rad/s
s : wheel slip ratio, [-]
αw : wheel slip angle, rad/s
ζ : wheel slip angle, rad/s
Fx : longitudinal tire force, N
Fz : vertical tire force, N
Lp : virtual preview distance, m
κ : curvature, m-1
R : turning radius, m
lf : distance of front wheel and mass center, m
lr : distance of rear wheel and mass center, m
tw : track width, m
λ : forgetting factor, [-]
e : velocity error, [m/s]
C : sensitivity gain, [-]
γ : adaptation gain, [-]
α : convergence gain, [-]
ρ : magnitude of injection term, [-]
fl : front left
fr : front right
rl : rear left
rr : front left

Acknowledgments

A part of this paper was presented at the KSAE 2021 Spring Conference

References

  • Y. Wang, C. Zong, K. Li and H. Chen, “Fault-Tolerant Control for In-Wheel-Motor-Driven Electric Ground Vehicles in Discrete Time,” Mechanical Systems and Signal Processing, Vol.121, pp.441-454, 2019. [https://doi.org/10.1016/j.ymssp.2018.11.030]
  • T. Chen, L. Chen, X. Xu, Y. Cai, H. Jiang and X. Sun, “Passive Fault-Tolerant Path Following Control of Autonomous Distributed Drive Electric Vehicle Considering Steering System Fault,” Mechanical Systems and Signal Processing, Vol.123, pp.298-315, 2019. [https://doi.org/10.1016/j.ymssp.2019.01.019]
  • J. Zhao, X. Wang, Z. Liang, W. Li, X. Wang and P. K. Wong, “Adaptive Event-Based Robust Passive Fault Tolerant Control for Nonlinear Lateral Stability of Autonomous Vehicles with Asynchronous Constraints,” ISA Transactions, Vol.127, pp.310-323, 2022. [https://doi.org/10.1016/j.isatra.2021.08.038]
  • W. B. Na, C. H. Park, H. C. Lee, S. J. Lee and S. O. Yu, “Sensitivity Applied Model-Based Fault Diagnosis Algorithm for Vehicle Control System Sensors,” Transactions of KSAE, Vol.26, No.3, pp.378-388, 2018. [https://doi.org/10.7467/KSAE.2018.26.3.378]
  • R. Wang and J. Wang, “Fault-Tolerant Control for Electric Ground Vehicles with Independently-Actuated In-Wheel Motors,” Journal of Dynamic Systems, Measurement, and Control, Vol.134, No.2, Paper No.021014, 2012. [https://doi.org/10.1115/1.4005050]
  • N. J. Jeon and H. C. Lee, “Integrated Fault Diagnosis Algorithm for Driving Motor of In-Wheel Independent Drive Electric Vehicle,” Transactions of KSAE, Vol.24, No.1, pp.99-111, 2016. [https://doi.org/10.7467/KSAE.2016.24.1.099]
  • G. Zhang, H. Zhang, X. Huang, J. Wang, H. Yu and R. Graaf, “Active Fault-Tolerant Control for Electric Vehicles with Independently Driven Rear In-Wheel Motors Against Certain Actuator Faults,” IEEE Transactions on Control Systems Technology, Vol.24, No.5, pp.1557-1572, 2015. [https://doi.org/10.1109/TCST.2015.2501354]
  • B. Zhang, S. Lu, W. Wu, C. Li and J. Lu, “Robust Fault-Tolerant Control for Four-Wheel Individually Actuated Electric Vehicle Considering Driver Steering Characteristics,” Journal of the Franklin Institute, Vol.358, No.11, pp.5883-5908, 2021. [https://doi.org/10.1016/j.jfranklin.2021.05.034]
  • B. Deng, K. Shao and H. Zhao, “Adaptive Second Order Recursive Terminal Sliding Mode Control for a Four-Wheel Independent Steer-by-Wire System,” IEEE Access, Vol.8, pp.75936-75945, 2020. [https://doi.org/10.1109/ACCESS.2020.2989326]
  • C. Hu, Y. Qin, H. Cao, X. Song, K. Jiang, J. J. Rath and C. Wei, “Lane Keeping of Autonomous Vehicles Based on Differential Steering with Adpative Multivariable Super-Twisting Control,” Mechanical Systems and Signal Processing, Vol.125, pp.330-346, 2019. [https://doi.org/10.1016/j.ymssp.2018.09.011]
  • S. Zou and W. Zhao, “Synchronization and Stability Control of Dual-Motor Intelligent Steer-by-Wire Vehicle,” Mechanical Systems and Signal Processing, Vol.145, Paper No.106925, 2020. [https://doi.org/10.1016/j.ymssp.2020.106925]
  • T. W. Kim, W. C. Kim, S. W. Choi and H. J. Kim, “Path Tracking for a Skid-Steer Vehicle Using Model Predictive Control with On-Line Sparse Gaussian Process,” IFAC-PapersOnLine, Vol.50, No.1, pp.5755-5760, 2017. [https://doi.org/10.1016/j.ifacol.2017.08.1140]
  • G. Reina and R. Galati, “Slip-based Terrain Estimation with a Skid-Steer Vehicle,” Vehicle Systems Dynamics, Vol.54, No.10, pp.1384-1404, 2016. [https://doi.org/10.1080/00423114.2016.1203961]
  • A. Vahidi, A. Stefanopoulou and H. Peng, “Recursive Least Squares with Forgetting for Online Estimation of Vehicle Mass and Road Grade: Theory and Experiments,” Vehicle System Dynamics, Vol.43, pp.31-55, 2005. [https://doi.org/10.1080/00423110412331290446]
  • H. J. Kim, S. C. Oh and K. S. Oh, “Development of an Algorithm for Wheel Speed Control of Autonomous Vehicles Lane Change using Virtual Preview Point,” KSAE Spring Conference Proceedings, pp.313-314, 2021.

Fig. 1

Fig. 1
Model schematics of skid steer based lane change algorithm

Fig. 2

Fig. 2
3rd polynomial function based on path planning

Fig. 3

Fig. 3
Kinematic analysis of skid steer method

Fig. 4

Fig. 4
Model schematics of proposed control algorithm

Fig. 5

Fig. 5
Wheel dynamics and wheel slip angle

Fig. 6

Fig. 6
Model schematics of performance evaluation

Fig. 7

Fig. 7
Wheel velocity (case [1])

Fig. 8

Fig. 8
Velocity error (case [1])

Fig. 9

Fig. 9
Estimated sensitivity gain (case [1])

Fig. 10

Fig. 10
Forgetting factor (case [1])

Fig. 11

Fig. 11
Input coefficients (case [1])

Fig. 12

Fig. 12
Disturbance terms (case [1])

Fig. 13

Fig. 13
Wheel torque control input (case [1])

Fig. 14

Fig. 14
Frequency analysis : Fourier transform (case [1])

Fig. 15

Fig. 15
Trajectory (case [1])

Fig. 16

Fig. 16
Longitudinal velocity (case [1])

Fig. 17

Fig. 17
Lateral velocity (case [1])

Fig. 18

Fig. 18
Longitudinal acceleration (case [1])

Fig. 19

Fig. 19
Lateral acceleration (case [1])

Fig. 20

Fig. 20
Yaw rate (case [1])

Fig. 21

Fig. 21
Wheel velocity (case [2])

Fig. 22

Fig. 22
Velocity error (case [2])

Fig. 23

Fig. 23
Estimated sensitivity gain (case [2])

Fig. 24

Fig. 24
Adaptive forgetting factor (case [2])

Fig. 25

Fig. 25
Estimated input coefficients (case [2])

Fig. 26

Fig. 26
Estimated disturbance terms (case [2])

Fig. 27

Fig. 27
Wheel torque control input (case [2])

Fig. 28

Fig. 28
Frequency analysis : Fourier transform (case [2])

Fig. 29

Fig. 29
Trajectory (case [2])

Fig. 30

Fig. 30
Longitudinal velocity (case [2])

Fig. 31

Fig. 31
Lateral velocity (case [2])

Fig. 32

Fig. 32
Longitudinal acceleration (case [2])

Fig. 33

Fig. 33
Lateral acceleration (case [2])

Fig. 34

Fig. 34
Yaw rate (case [2])

Table 1

Vehicle parameters for performance evaluation

Vehicle parameters
Description Value Units
Vehicle mass 1,463 [kg]
Moment of inertia 1,600 [kgm2]
Distance between front axis and mass center 0.96 [m]
Distance between front axis and mass center 1.577 [m]
Track width 1.561 [m]
Wheel radius 0.3085 [m]

Table 2

Performance evaluation scenario

Performance evaluation scenario
Div-1 Case [1] Case [2]
Description Longitudinal velocity
Value [unit] 10 [kph] 30 [kph]
Div-2 Case [1-1] Case [1-2] Case [1-3] Case [1-4] Case [2-1] Case [2-2] Case [2-3] Case [2-4]
Description SMC CF SMC AF SMC AF SMC SMC CF SMC AF SMC AF SMC
Description Sample time
Value [unit] 0.001 0.0001 0.001 0.0001

Table 3

Performance evaluation control parameters, case [1]

Control parameters
Div-1 Case [1-1] Case [1-2] Case [1-3] Case [1-4]
Description unit value
Preview time [sec] 10 10 10 10
Time constant for driving path [sec] 0.1 0.1 0.1 0.1
Proportional gain for driving path [-] 1 1 1 1
Derivative gain for driving path [-] 0.0001 0.0001 0.0001 0.0001
Integral gain for driving path [-] 0.0001 0.0001 0.0001 0.0001
Initial value of estimated coefficients [-] [-] [-0.01
0.01]
[-0.01
0.01]
[-0.01
0.01
Initial value of covariance matrix [-] [-] [0.01
0.01]
[0.01
0.01]
[0.01
0.01
Forgetting factor for sensitivity gain [-] [-] [-] 0.5 0.5
Adaptation gain [-] [-] [-] 3 1
Forgetting factor [-] [-] 0.999 Time-varying Time-varying
input coefficients [-] 0.01 Timev-arying Time-varying Time-varying
Disturbance terms [-] 5 Timev-arying Time-varying Time-varying
Convergence gain [-] 3 3 3 3
Time constant for control input [sec] 0.2 0.2 0.2 0.02
Sample time [sec] 0.001 0.0001

Table 4

Analysis of error distribution (case [1])

Div-1 Div-2 Average Standard deviation
Case [1-1] Wheel FL -0.000,201 0.005,9
Wheel FR -0.000,354 0.005,9
Wheel RL -0.000,064 0.009,3
Wheel RR 0.000,012 0.009,2
Case [1-2] Wheel FL -0.000,410 0.004,0
Wheel FR -0.000,069 0.004,8
Wheel RL -0.000,338 0.004,1
Wheel RR -0.000,250 0.004,5
Case [1-3] Wheel FL -0.000,350 0.002,8
Wheel FR 0.000,272 0.005,7
Wheel RL -0.000,329 0.002,9
Wheel RR 0.000,340 0.006,1
Case [1-4] Wheel FL -0.000,412 0.004,3
Wheel FR -0.000,220 0.001,1
Wheel RL -0.000,438 0.004,6
Wheel RR -0.000,231 0.001,1

Table 5

Performance evaluation control parameters, case [2]

Control parameters
Div-1 Case [2-1] Case [2-2] Case [2-3] Case [2-4]
Description unit value
Preview time [sec] 10 10 10 10
Time constant for driving path [sec] 0.1 0.1 0.1 0.1
Proportional gain for driving path [-] 1 1 1 1
Derivative gain for driving path [-] 0.0001 0.0001 0.0001 0.0001
Integral gain for driving path [-] 0.0001 0.0001 0.0001 0.0001
Initial value of estimated coefficients [-] [-] [-0.01
0.01]
[-0.01
0.01]
[-0.01
0.01
Initial value of covariance matrix [-] [-] [0.01
0.01]
[0.01
0.01]
[0.01
0.01
Forgetting factor for sensitivity gain [-] [-] [-] 0.5 0.5
Adaptation gain [-] [-] [-] 3 1
Forgetting factor [-] [-] 0.999 Time-varying Time-varying
input coefficients [-] 0.01 Time-varying Time-varying Time-varying
Disturbance terms [-] 5 Time-varying Time-varying Time-varying
Convergence gain [-] 3 3 3 3
Time constant for control input [sec] 0.2 0.2 0.2 0.09
Sample time [sec] 0.001 0.0001

Table 6

Analysis of error distribution (case [2])

Div-1 Div-2 Average Standard deviation
Case [2-1] Wheel FL -0.000,402 0.001,70
Wheel FR -0.000,394 0.001,70
Wheel RL -0.000,406 0.002,70
Wheel RR -0.000,417 0.002,70
Case [2-2] Wheel FL -0.000,412 0.000,98
Wheel FR -0.000,419 0.001,30
Wheel RL -0.000,424 0.001,10
Wheel RR -0.000,425 0.001,40
Case [2-3] Wheel FL -0.000,409 0.000,93
Wheel FR -0.000,307 0.000,73
Wheel RL -0.000,405 0.000,90
Wheel RR -0.000,311 0.000,79
Case [2-4] Wheel FL -0.000,181 0.000,36
Wheel FR -0.000,173 0.000,44
Wheel RL -0.000,189 0.000,37
Wheel RR -0.000,127 0.000,31