Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle

Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle

Accepted Manuscript Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle Noor ...

2MB Sizes 3 Downloads 40 Views

Accepted Manuscript Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle Noor Hafizah Amer, Khisbullah Hudha, Hairi Zamzuri, Vimal Rau Aparow, Amar Faiz Zainal Abidin, Zulkiffli Abd Kadir, Muhamad Murrad

PII: DOI: Reference:

S0921-8890(18)30090-3 https://doi.org/10.1016/j.robot.2018.03.006 ROBOT 3004

To appear in:

Robotics and Autonomous Systems

Received date : 5 February 2018 Revised date : 28 February 2018 Accepted date : 23 March 2018 Please cite this article as: N.H. Amer, K. Hudha, H. Zamzuri, V.R. Aparow, A.F.Z. Abidin, Z.A. Kadir, M. Murrad, Adaptive modified Stanley controller with fuzzy supervisory system for trajectory tracking of an autonomous armoured vehicle, Robotics and Autonomous Systems (2018), https://doi.org/10.1016/j.robot.2018.03.006 This is a PDF file of an unedited manuscript that has been accepted for publication. As a service to our customers we are providing this early version of the manuscript. The manuscript will undergo copyediting, typesetting, and review of the resulting proof before it is published in its final form. Please note that during the production process errors may be discovered which could affect the content, and all legal disclaimers that apply to the journal pertain.

Adaptive Modified Stanley Controller with Fuzzy Supervisory System for Trajectory Tracking of an Autonomous Armoured Vehicle Noor Hafizah Amer1,2. Khisbullah Hudha1. Hairi Zamzuri2. Vimal Rau Aparow1. Amar Faiz Zainal Abidin3. Zulkiffli Abd Kadir1. Muhamad Murrad1 1

Faculty of Engineering, Universiti Pertahanan Nasional Malaysia, 57000, Kuala Lumpur, Malaysia

2

Malaysia-Japan International Institute of Technology, University Technology Malaysia, 54000, Kuala Lumpur, Malaysia

3

Faculty of Engineering Technology, Universiti Teknikal Malaysia Melaka, 76100 Durian Tunggal, Melaka, Malaysia

Abstract In developing path tracking controller for autonomous vehicles, a properly tuned controller will work well for a certain range of driving conditions but may need to be re-tuned for others. This study presents the development of an adaptive controller with Fuzzy Supervisory system for trajectory tracking control of an autonomous armoured vehicle. A knowledge database is built using Particle Swarm Optimisation which is the mainframe of the Fuzzy supervisory system in adapting to various trajectories and speed. The proposed controller is simulated on a nonlinear vehicle model, and experimental results for the controller are presented to evaluate the proposed controller.

Keywords: Armoured Vehicle, Autonomous Trajectory Tracking, Path Tracking, Stanley Controller, Particle Swarm Optimisation, Fuzzy Supervisory

Corresponding Author: Noor H. Amer, Faculty of Engineering, Universiti Pertahanan Nasional Malaysia, 57000, Kuala Lumpur, Malaysia Email: [email protected] Tel: +60193421407 Fax: +60390513472

1

1 Introduction Main objective of this study is to develop an adaptive controller to provide automatic steering input for an unmanned armoured vehicle. For a vehicle to be driven autonomously, the control architecture usually consists of sensors fusion to collect data from vehicle surroundings, perception module to process data collected, planner to plan the vehicle trajectory, tracking control to follow the trajectory and keeping the vehicle on the intended course, and lastly, actuator control module to ensure required actuation from tracker can be realized physically [1]. Trajectory tracking control is one of the most advancing topics in the past decade. It is usually a controller module aimed to provide automatic actuation to the vehicle system while guiding the vehicle autonomously. This module may or may not depend on a separate path planner to plan an intended course for the vehicle (and controller) to follow. In trajectory tracking controller, one of the most common strategies is geometric/kinematic based controllers. This type of controllers determines the required steering input based on the vehicle’s geometric and kinematic properties such as acceleration, velocity and position. These are easier to obtain compared to kinetic properties such as forces and torques that are usually used in dynamic controllers. Among geometric/kinematic controllers such as Follow-the-carrot [2, 3], Pure Pursuit [4-9] and other geometric controllers [10-14], Stanley method is one of the established controllers. It was used on the autonomous vehicle Stanley by Stanford University that won the DARPA Challenge 2005 [15]. Main difference of this controller compared to other notable geometric/kinematic controllers is that it does not depend on look-ahead distance to guide the vehicle automatically. Instead, the steering command includes yaw rate error feedback between vehicle’s and trajectory yaw rates to determine the steering angle. This controller has been proven to show good performance in autonomous steering control in several studies previously [16-20]. In addition, this work contributes academic resources to studies on unmanned armoured vehicles which are known to be limited due to its confidentiality nature [21]. However, further investigation into Stanley performance yield that the controller depends on the parameter tuning process, which is a common problem with most geometric/kinematic controllers. A properly tuned geometric/kinematic controller will work well for a type of road course and certain range of vehicle speed [16, 19, 22]. Several methods have been proposed to tune the controllers [19, 20]. However, if the controller parameters are finely tuned for a specific manoeuvring condition, the optimal set of parameters may not be suitable for different conditions which require the controller to be re-tuned to perform satisfactorily. Therefore, an adaptive controller is proposed in this study to automatically tune the parameters depending on vehicle state and trajectory heading. Due to its proven performance, Stanley controller has been chosen as the base command for the proposed adaptive controller. Basic Stanley controller in [16] is modified to be more sensitive to changes in trajectory and vehicle speed before the adaptive algorithm is applied. Adaptive controller has been an active research fields. One of good prospects in adaptive controller is employing intelligent adaptive mechanisms to established controllers such as sliding mode controller and PID using intelligent learning mechanisms [23-26]. In autonomous steering 2

control, adaptive controllers have been proposed in several studies previously [27-30]. This type of controller is usually proposed to increase the robustness of the controller in adapting to different manoeuvring conditions. Several aspects have been considered for a controller that can adapt to conditions such as unknown skidding conditions [27] and variable slip conditions [28, 29]. While the proposed controllers in these studies were proven to adapt to the catered conditions, it may not be able to cater unexpected disturbances in other aspects such as variable vehicle parameters and road curvatures. Also, most steering controllers were developed using a linear vehicle model which neglects nonlinear interactions such as tyre frictions, variations in vertical tyre forces, aerodynamics, rolling frictions, and steering system dynamics. While this approach is valid especially in low accelerations and small slip conditions, developing controller using linearized interaction assumptions can pose underestimation of vehicle states. This can be problematic especially in estimating controller parameters value for a bigger and heavier vehicle such as armoured vehicle which may possess different dynamic behaviours during manoeuvrings. In order to address these issues, the main contribution of this research is on the development of an adaptive controller on an armoured vehicle to cater variations in speed and road trajectory. Controller parameters will be automatically tuned based on vehicle speed and heading error between vehicle and trajectory instantaneous directions. This can address the flexibility issue always associated with geometric/kinematic controllers. Also, it improves the controller’s ability to navigate sharp turns which is also a common problem in autonomous trajectory tracking [31]. The adaptive controller is developed using a full vehicle model for a nonlinear armoured vehicle. It can be noted that trajectory following controller has not been studied or employed on an armoured vehicle previously. A fuzzy supervisory system is used for the adaptive mechanism in automatically tuning the parameters. Another contribution of this paper is that the system is developed using a knowledge database which is built by optimising the controller parameters for various input combinations using Particle Swarm Optimisation (PSO). This is different than intuitive rules and mathematical adaptive mechanisms proposed previously [26, 32, 33]. Effectiveness of the controller is analysed by simulating the controller on different roads and operating speed. Finally, the control signals from the controller is validated against human driver through a set of experiments. To summarise, the contributions are presented into five (5) main aspects in proposing the adaptive controller: 1. Development of the controller is using a non-linear vehicle model to ensure the simulated vehicle response to be as close as possible to real conditions and accurate parameter tuning; 2. Vehicle speed and heading error, which are related to the turning curvature and vehicle slips, are chosen for the adaptive input. This is to increase the controller’s ability in adapting to various manoeuvring conditions; 3. Using modified Stanley controller as the base controller due to its simple and proven ability. 4. Adaptive mechanism is developed using fuzzy inference system and optimum knowledge database that is optimised using PSO

3

5. The validation experimental setups and procedure is presented to verify the controller ability in generating realistic steering command compared against human driver. Main methodology used in this research is using modified Stanley controller as the base control law to increase its sensitivity to parameter variations. With this, a knowledge database is built by optimising the controller parameters for each combination of speed and heading error inputs using Particle Swarm Optimisation. Range for the inputs are set to be 0-72 km/h for vehicle speed input, and 0-75 deg in both directions for vehicle’s heading error input. Upon finalizing knowledge database, a Fuzzy Inference System is developed to supervise the automatic parameter tuning. The proposed controller is then tested on different road courses that represent various manoeuvring conditions. Simulated steering input from the controller is then validated against experimental results from human driver to observe the conformity between the two responses. Structure of this paper is as follows. First section contains brief introduction on trajectory tracking and previous researches on the field, as well as overview of the research conducted in this study. This is followed by the development of a 7 degree-of-freedom (DOF) armoured vehicle model in Section 2. Section 3 presents the development of the adaptive controller with Fuzzy supervisor proposed in this study. Meanwhile, Section 4 describes the simulation and experimental procedures. Simulation results and experimental validations are presented in Section 5, while section 6 presents the conclusions for this work. 2 Modelling of an Armoured Vehicle An armoured vehicle model is developed to simulate vehicle responses from the armoured vehicle system during controller development process. A nonlinear armoured vehicle model is used, consists of several modules to represent each component on the vehicle as shown in Fig. 1, where the side view of the considered armoured vehicle is shown in Fig. 2. Several assumptions were made in developing this model. Firstly, development of this model is aimed for studies on vehicle handling. Main concerns are on the vehicle motions in longitudinal plane where the suspension units are considered ideal. Also, the vehicle is assumed to travel on even road where vertical disturbances are ignored. Thus, vertical forces are determined using load distribution equations by evaluating the load transfer between tyres during manoeuvrings. In longitudinal plane, effect of air and rolling resistance are included to improve the accuracy of the responses. Detail development and verification of this model has been presented in previous publication by authors [34-36]. To avoid lengthy descriptions, only main equations are presented herewith. The sign conventions for force and angular directions in vehicle system are as suggested by [37].

4

Fig. 1: Schematic ddiagram of the aarmoured vehiclle model

Fig. 2: Sidee view of the arm moured vehicle

Handling Moodel 2.1 H Handlinng model inn the armouured vehiclee system is developed tto simulate vehicle ressponses in longituddinal plane bby evaluatinng equationns of motionns in x and y directionss as well as rotational motion about z axis, namely yaw. Thesee motions ccontribute tthree degreee-of-freedom ms (DOF) while annother fourr DOF are ccontributed by the inddependent rootational m motions of thhe wheels about itts rotationall axis. An additional a d disturbance of firing foorce is considered in thhis model, which can c be obtaained by evaaluating reccoil force frrom a gun model as ddetailed prevviously in [38]. Thhis can bee useful in studies whhere firing--on-the-movve is conceerned. In thhis study, however, this effectt is not conssidered and therefore, FR = 0.

5



CG

t

v

Fig. 3: Armoured vehicle in longitudinal plane

Eqs. (1) – (3) show the three DOF equation of motions derived for the handling model. Based on Fig. 2 and Fig. 3, the vehicle is considered moving on road with slope θ = 0, with sprung mass (mb); moment of inertia of the sprung mass about z-axis (ICG); longitudinal motion in x-direction with acceleration (ax); lateral motion in y-direction with acceleration (ay), and yaw motion about z-axis with yaw angle (ψ). Each wheel is denoted based on their position with subscript i, j, where i = front(f)/rear(r), and j = left(l)/right(r). Here, Fxij and Fyij denotes the longitudinal and lateral forces acting on each wheel, respectively, and Mz,ij is the self-alignment moment, Mz of each wheel. These are obtained from the tyre model. Fxrr  Fxrl  Fxfl cos   Fyfl sin   Fxfr cos   Fyfr sin   mb g sin   Fd  FR cos   mb ax

(1)

Fyrr  Fyrl  Fxfl sin   Fxfr sin   Fyfl cos   Fyfr cos   FR sin   mb a y

(2)

M

zij

  Fyrr  Fyrl  lr   Fxfl sin   Fyfl cos   Fxfr sin   Fyfr cos   l f

(3) t   FR sin   cR   Fxfr cos   Fxfl cos   Fyfl sin   Fyfr sin   Fxrl  Fxrr   ICG 2 The lateral and longitudinal accelerations obtained in above equations are further affected by the vehicle yaw motion during manoeuvrings. The effect is generalised in Eq. (4) as presented before in [35-37, 39]. Here, vx and vy denotes the effective accelerations in longitudinal and lateral directions, respectively.

vx  a x  v y v y  a y  vx

(4)

Another four DOF from rotational motion of each wheel about its axis can be generalized into one equation in Eq. (5). Here, similar definition of ij are adopted as before. τr is the reaction torque generated by the traction force due to the wheel’s longitudinal force, Fx,ij. τd is the friction 6

torque for a wheel with viscous friction coefficient, τb is the braking torque and τe is the engine torque supplied to driving wheels. Full derivation of Eq. (5) and equations for Fd, τr, τd can be found in [35, 40]. This study considers constant speed manoeuvrings, therefore, τb and τe are both zero.

 e ,ij   r ,ij   b ,ij   d ,ij  I y ,ij ij

(5)

2.2 Tyre Model Tyre model is the element to estimate contact forces generated between tyre and road surface, Fx and Fy, as well as the self-alignment moment during manoeuvrings, Mz. Pacejka Tyre Model, also known as Magic Formula is adopted in this study to represent the tyre equations. General equation for Magic Formula is shown in Eq. (6) [41, 42]. Here, P represents specific function of either Fx, Fy, or Mz with same form of general equation containing parameters B, C, D, , Sh, and Sv . These parameters represent the stiffness factor, shape factor, peak value, curvature factor, horizontal shift, and vertical shift properties of the function, respectively with different values for each function of Fx, Fy, or Mz. Similar applications for this tyre model can be found in previous publications [35, 43, 44].

P  Fz ,  ,    D sin  C arctan  B    Sv

(6)

Shape factor, C and Peak factor, D is calculated by Eq. (7) and (8) respectively. By evaluating Eq.(9) or (10), one can calculate the stiffness factor, B = BCD/CD. Here, subscripts Fx, Fy, or Mz denotes the function it corresponds to.

C  a0

(7)

D  a1 Fz 2  a2 Fz

(8)

 BCD  Fx / Mz  BCD  Fy

  a 3 Fz 2  a 4 Fz  e  b5 Fz

 a 3 sin  a 4 arctan  a 5 Fz  

(9) (10)

Curvature factor, , for each function can be evaluated using Eq. (11) for Fy, and Mz and Eq. (12) for Fx where E, Sh, and Sv can be determined using Eq. (13)-(15) respectively. With these equations, one can determine lateral force, longitudinal force and self-aligning moment for each wheel. All parameters needed are listed in Table 1. These parameters are based on previously published data for commercial vehicles [37, 41, 45]. Since the small scale armoured vehicle used in this study is using the same tyre as being used on a commercial vehicle, these values are used. It should be noted that in accordance to ISO standard definition of slip angle, the direction for Fy and Mz should be reversed when applied to a vehicle model with ISO standard notations.

 Fy / Mz  1  E   Sh     Fx  1  E   Sh  

E arctan  B   S h   B

E arctan  B   S h   B

(11) (12) 7

E  a6 Fz 2  a7 Fz  a8

Sh  a9

(13)

 Sh  Fx  0

S v   a10 Fz 2  a11 Fz  

 S v  Fx

(14) 0

(15)

Table 1: Parameters for Magic formula for Pacejka Tyre Model [41, 45]

a0

a1

a2

a3

a4

a5

a6

a7

a8

a9

a10

a11

1.3

-22.1

1011

1078

1.82

0.208

0

-0.354

0.707

0.028

0

14.8

-2.72 -21.3

-2.28 1144

-1.86 49.6

-2.73 226

0.11 0.069

-0.07 -0.006

0.0643 0.056

-4.04 0.486

0.015

-0.066

0.945

Fy Mz 2.4 Fx 1.65

Main input for this model is the tyre slip angle, α, and longitudinal slip, σ, formulated in Eq. (16) and (17), respectively. Another input is tyre vertical force, Fz, which evaluated using load distribution equation to consider the load transfer process in manoeuvrings as shown in Eq. (18). All notations are based on Figures 1 and 2, where i = front(f)/rear(r), j=left/right and for nonsteerable wheels,  rl   rr  0 . lf and lr are the distance between vehicle’s centre of gravity to the front and rear axles, respectively. For longitudinal slip, ωij is the rotational speed of each tyre respectively, and Rij is the tyre radius. Details on model and derivations can be found in [35, 43, 44]. For the load distribution equation in (18), h and θ represent the height of armoured vehicle and road slope, respectively as shown in Figures 1 and 2.    v y  l f      fj Lateralslips,  fj  tan 1   v   t    x  2      v y  lr     rj  rj  tan 1   v   t    x  2  

Longitudinalslips,  ij 

vx  ij  Rij  max (vx ,ij Rij )

 h l  mg Fz , f j    lr cos   h sin     ma y    f    t  l  2t Fz ,r j

   max  h          2  l 

 mg    h   l    ma  h   l f cos   h sin      ma y    r     x       2t    t   l   2  l 

(16)

(17)

(18)

8

2.3 Vehicle Kinematic Model This equation determines the vehicle’s position with respect to global coordinates (X-Y) based on the instantaneous speed and yaw angle. Based on [43, 46], vehicle position in lateral and longitudinal direction with respect to global axes, X and Y respectively, can be obtained from Eq. (19). Here, ψ is the vehicle yaw angle, vx , v y are the body-fixed vehicle longitudinal and lateral velocities, respectively, and X0, Y0 are the initial positions in X-Y axes, respectively.

X 

X0

0

Y 

Y0

0

v

v

x

x

cos  v y sin  dt

(19)

sin  v y cos  dt

In simulating the vehicle model, vehicle parameters as listed in Table 2 are used. These parameters are extracted from High Mobility Multipurpose Wheeled Vehicle (HMMWV) model in CARSIM software. While some specific parameters such as the width and height of the vehicle are taken from the actual dimension from our armoured vehicle, the basic parameters can be obtained from the vehicle specification data in CARSIM. Full modelling, development, and verification procedures for the armoured vehicle used in this study can be found in previous publication by authors [35]. Table 2: Parameter of Armoured Vehicle Model [35]

Symbol Iw A mb mw Rw g Cd Cr lf lr h t Iyaw

Description Wheel inertia Frontal area Vehicle body mass Wheel mass Tyre radius Gravitational acceleration Aerodynamic resistance Rolling resistance Front length from COG Rear length from COG Height of vehicle from COG Vehicle width Yaw inertia

Value 15 kg. m2 0.05m2 2210 kg 100 kg 0.468 mm 9.81 m/s2 0.29 0.01 1070 mm 2230 mm 660 mm 1900 mm 4300 kg. m2

3 Development of Adaptive Controller for Trajectory Tracking An adaptive trajectory tracking controller is developed for the armoured vehicle using Fuzzy Supervisory method. Basically, the controller obtained the trajectory input from a pre-defined road course which is explained in detail within Section 4.1. A suitable steering correctional angle, δ, to guide the armoured vehicle is then determined using steering command as presented in this section. Overall, an adaptive strategy with Fuzzy supervisor is proposed to automatically adjust controller parameters in adapting to varying vehicle conditions. Overall structure of the proposed controller is shown in Fig. 4. Following sub-section describes the development of the adaptive controller starting with the base, non-adaptive controller, and development of Fuzzy Supervisory System based on knowledge database optimised with Particle Swarm Optimisation. 9

Fig. 4:: Structure of Addaptive controlller with Fuzzy SSupervisor

king Controol based on Stanley Coontroller 3.1 Basic Trajecctory Track Eq. (20) is chosen to A basicc steering coommand froom Stanley Controller [16, 17] as shown in E mple formullation and developp the trajecttory trackingg controllerr used in thhis study duue to its sim effectiveeness in guuiding a wiinning vehiicle, namelyy Stanley iin DARPA Challenge [15]. An extended version of o the Stanleey controlleer is presentted in the saame publicaation as shoown in Eq. (21) to include thee effect of yyaw rate errror in deterrmining thee steering innput. This vversion of controller has beenn applied on the same armoured veehicle in preevious studyy [20]. In thiis study, a modified version oof Stanley iss used withh minor moddifications to t increase the sensitivvity of the basic coontroller too the changging in vehhicle states. The moddified contrroller, herebby named Modifieed Stanley C Controller (M Mod St) inccludes a tunne-able gain,, k , as show wn in Eq. (222). Here, is thee heading errror (rad) beetween the vehicle’s diirection of ttravel and thhe instantanneous path directionn; e is the llateral errorr (m) defineed as the shhortest distannce betweenn vehicle annd nearest point onn path; v iss the vehiclle speed (m m/s);  and traj are thee instantaneeous yaw raate of the vehicle and trajectoory (rad/s),, respectivelly, and k , k1, k, and kψ are tuneaable gains. Graphical interpretation of thee parameterrs is shown in Fig. 5. In I this papeer, the originnal Stanley controller (St) in Eq. (20) w will be useed as the m main benchhmark togetther with thhe Modified Stanley Controlller (Mod Stt) to evaluate the effectiiveness of thhe proposedd adaptive coontroller.

 kke  t     v t  

    tan 1 

 ke  t     k   traj   1 v t  

  t     arcttan 

 ke  t     k   traj   1 v t  

  t   k  k1 arrctan 

(20)

(21)

(22)

10

Fig. 5: Parameters for f the steeringg command form mulation

In tuninng the paraameters, Sniider [19] haas outlined tuning proocedure for the originaal Stanley controller using triial and erroor method. IIn this studdy, Particle Swarm Opptimisation iis used to optimisee the controoller parameeters as outllined by preevious studiies by authoors [20, 47].. Constant speed iss assumed, and therefo fore, each ccontroller is optimised for each trrajectory annd vehicle speed. D Detail analyysis of Modiified Stanleyy controller and its appplication on the armoureed vehicle can be sseen in [48]. Further tunning of the controller yyields the fact that eachh tuned param meter will only be optimised for a set off trajectory and speed vvalues. For controllers with more tune-able parametters, it will increase thhe sensitivitty and thereefore, worssen the conttroller’s perrformance with varrying vehiclle conditionns. This cann be demonsstrated in Fiig. 6, whichh shows thee result on varying the constaant vehicle speed in naavigating a single trajeectory. Therefore, a suupervisory method is developeed to enable the controlller to adapt to changingg speed and trajectory. Variatio on of speed for f Modified Stanley (Mod St) Contro oller 600

V = 18 8 ms-1 = 65 km/h

400

V = 12 2 ms = 43 km/h

200

-1

-1

V = 6 ms m = 22 km/h Trajec ctory

Y - Position (m) ( )

0 0

200

400

600

800

1000

V Variation of speed s for Sttanley (St) Controller 500

413.2 412.8 412.4 625.2

0 0

625.22 625.24 625.26

200

400

600

800

1000

Variation of o speed for St-Yaw controller 500

0 0

200

400

600

800

1000

X - Positio on (m)

11

Fig. 6. Effect of varying speed for Original Stanley Controller (Eq.(20)), Stanley Controller with Yaw compensation (ST-Yaw – Eq.(21)), and Modified Stanley Controller (Mod St – Eq. (22))

3.2 Development of Optimal Knowledge Database Using Particle Swarm Optimisation In developing the adaptive algorithm for the controller, a knowledge database was built to provide insights and experience to the controller in deciding the suitable values of controller parameters. Since the decisions will be made based on vehicle speed, v and heading error, , the knowledge database should have a complete set of parameters, namely k , k1, k, and kψ, for each combination of inputs v and . For each input, several values were chosen as listed in Table 3. The interval between two values cannot be too large to avoid inaccuracy in the control surface. The interval cannot be too small which will make the data to be too exhaustive. Minimum of 1 m/s (  3.6 km/h) and maximum of 20 m/s (  72 km / h ) were chosen to limit the manoeuvring speed allowable for the vehicle due to safety precautions. Minimum and maximum values of 1 deg and 75 deg for were chosen to enable the vehicle to negotiate sharp corners of up to 75 deg. Each combination of these input values is used in the simulation where the controller is optimised to find the desired parameter values. With this, the finalized knowledge database contains 60 sets of controller parameters. Table 3: Interval for knowledge database for each input

v (m/s)

1

5

10

15

20

(deg)

1

5

15

30

45

60

75

-1

-5

-15

-30

-45

-60

-75

For each input combination, all four parameters are optimised using Particle Swarm Optimisation method as outlined in previous studies [20, 47]. The algorithm is chosen due to it being one of the most common and established meta-heuristic optimisation algorithm along with Genetic Algorithm, and Ant Colonisation Algorithm. It is an approach to solve optimisation problems by emulating the motion of particles moving in swarms. Introduced in 1995 [49], the algorithm has seen various applications and advancements since then. Basically, the algorithm mimics the behaviour of particles in swarm with randomly assigned initial position that moves together towards the most optimum position. Each of the particles will have the memory of its own best position, pbest and the overall swarm best position, gbest based on the optimum fitness value. These memories will be considered in determining particle’s motion for its next position. This is to ensure that the agents are not too quick to move towards the new position which can avoid entrapment in local optimum solutions. In general, while each of the ith particle at position xid in each of the dth dimension moves with velocity v, the next position, xid(t+1) is determined by (23) and the next velocity, v(t+1) is determined by Eq. (24). Over several iterations, the whole swarm will find an optimum position (solution). In this study, PSO is used to optimise each combination of v and . The main objective of each optimisation is to minimize fitness function, which is quantified by the RMS values of lateral error, as shown in (25). Table 4 shows the parameter values used for the PSO algorithm, while the upper part of Fig. 7 shows overall procedure of optimising each input combinations using Particle Swarm Optimisation. Fitness function for the algorithm is the RMS values of lateral error, e throughout manoeuvring. The application of PSO in this study is similar to previous researches by authors [20, 47, 48]. 12

x  t  1id  x  t id  v  t  1

(23)

v ( t 1)  iw  v ( t )  c  rand(0,1) ( pbest ( t )  x ( t ) id )  s  rand(0,1) ( g best ( t )  x ( t ) id )

(24)

Fitness Function, f (k f , k1 , k , k y ) 

 e  t 

2

n

(25)

Table 4: PSO parameters used in building knowledge database [47], [20]

Parameter Social Coefficient, s Cognitive Coefficient, c Inertial Weight, iw No. of Dimensions, Nd Upper Bound Limit Lower Bound Limit No. of Particles, Np No. of Iterations, Ni

Values 1.42 1.42 0.9 4 (k1, k , k, and kψ) [10;10;10;10] [-10; -10; -10; -10] 150 20

13

Figg. 7: Procedurre in developingg Adaptive Stanlley controller with w Fuzzy Superrvisor

nt of Adaptiive Controlller with Fu uzzy Supervvisory Meth hod 3.3 Developmen m is proposeed for adaptive mechannism to the Modified In this ppaper, a Fuzzzy superviisory system Stanley Controller that will addjust the paarameter vallues dependding on the vehicle speeed, v and headingg error, innputs. The Fuzzy F superrvisory systtem consistss of variouss fuzzy setss of inputs which aare defined bby a Membeership Funcction (MF) aand connectted to each other o througgh a set of antecedeent rules whhich will deetermine thee system outtputs. As shhown in Fig.. 4, the inpuuts for the system are v and , respectivvely, while the outputss are the paarameter vaalues for thhe Mod St controller (k1, k , k, kψ). In ddefining thee Fuzzy suppervisory syystem, a Suugeno type of Fuzzy Inferencce System ((FIS) was chosen to suuit the know wledge databbase. Thereefore, no meembership functionn will be deefined for thhe defuzziffication stagge and consstant values from the kknowledge databasee will be ussed instead.. In fuzzificcation stage, Gaussian function is chosen to ddefine the 14

MF for both inputs of vehicle speed (v) and vehicle heading ( ). This function is chosen since it has only two parameters to define the overall function for each of variable value, x, namely the centre of the function, c and spread of the curve, σ. The Gaussian membership function used in the FIS is as shown in Eq. (26) where xi, i = 1, 2 denotes the function input variables of vehicle speed (v) and vehicle heading ( ), respectively. f  xi   e

1  x c    i  2  

2

 1  x  c 2   exp    i  2      

(26)

In the Fuzzy system, several fuzzy sets are established to define different range of each inputs. Each set is defined using a MF that will characterise membership state of any value to the specific fuzzy set using the Gaussian function in Eq. (26). Five and twelve sets of MF are defined for the speed and heading error input, respectively, which corresponds to the intervals in the knowledge database in Table 3. Fuzzy sets for both input is shown in Table 5, and the complete Gaussian graphs that define all sets of membership functions are shown in Fig. 8. Here, ‘S’ denotes Small, ‘B’ = Big, ‘R’ = Right, and ‘L’ = Left. At any given time, input values are taken for fuzzification to evaluate it level of membership in each fuzzy set using the membership function. Then, a set of rules are defined within the Fuzzy system to determine the output from any input or combination of input Fuzzy sets as shown in Table 6. In this study, AND rules are used to determine the output based on the membership values of the input in each rule which will be using product inference method. Theoretically, a Fuzzy inference system with singleton fuzzifier, centre-average defuzzifier, product inference, and Gaussian membership function can be presented mathematically by the expression in Eq. (27) [50-52]. Here, R, n, and bj are number of rules, number of inputs, and output values for each j-th rule, respectively. Each set of bj contains 4 values, denoted by bja which corresponds to each output, respectively. This is obtained from the knowledge database as developed in previous section. Also, x is the system inputs x = [x1, x2]T, and Ka is the a-th system output from K = [k1, k , k, kψ]T.  1  x  c j 2  b  exp    i j i     2  i   j 1 i 1   K a  f ( x)  n R  1  x  c j 2  exp    i j i     2  i   j 1 i 1   R

a j

n

(27)

Table 5: Fuzzy sets for input

x1 = v x2 =

SS

BS

B

SB

BB

LSS

LBS

LB

LSB

LBB

LBL

RSS

RBS

RB

RSB

RBB

RBL

15

Fig. 8: Gaaussian graphs ffor membershipp functions of innput variables

T Table 6: Fuzzy R Rules

x1 = v

F Fuzzy Rule Base

x2 = LS SS LBS

LB B

LSB LB BB

LBL

R RSS

RBS

RB

RSB

RBB

RB BL

SS

b1

b2

b3

b4

b5

b6

b7

b8

b9

b10

b11

b112

BS

b113

b14

b115

b16

b117

b18

b19

b20

b21

b22

b23

b224

B

b225

b26

b227

b28

b229

b30

b31

b32

b33

b34

b35

b336

SB

b337

b38

b339

b40

b441

b42

b43

b44

b45

b46

b47

b448

BB

b449

b50

b551

b52

b553

b54

b55

b56

b57

b58

b59

b660

Finally, Fuzzy suppervisory syystem for thhe adaptive Modified S Stanley conntroller are ddeveloped and cann be shown in i Fig. 9. T This system is to be inttegrated intoo the adaptivve trajectoryy tracking controller system as shown in F Fig. 4.

16

Fuzzy Supervisory System f(u)

k1 (60) f(u)

Velocity (5) (Sugeno)

k (60) f(u)

60 rules kyaw (60)

Theta (12)

f(u)

kpsi (60)

Fig. 9: Developed FIS for Fuzzy Supervisory System

4

Simulation of Adaptive Modified Stanley Controller with Knowledge Based Fuzzy Supervisory System 4.1 Simulation Procedures In evaluating the proposed adaptive controller, six road courses are developed as the road courses to represent different manoeuvrings for the vehicle to navigate. These road courses are shown in Fig. 10. The three first roads in the upper part of the figure represent short courses and sharp cornering manoeuvres where the vehicle is required to have multiple turns with small curvature roads within short range of less than 1 km. Another three roads represent trajectories with smooth curvatures or longer range of manoeuvrings of more than 1 km range. Simulating vehicle manoeuvrings on these roads will evaluate the versatility of the controller in navigating various trajectories and curvatures. Also, it is worth to note that the first road, namely Straight Road is based on an actual road from the vicinity of Kuala Lumpur where the coordinates were taken and converted into series of points to define the trajectory. It is also the same road that was used in previous studies by authors [20, 47]. Multiple Lane Change

Y - Position (m)

Straight Road

60

5

2

0 20

1 100

200

300

-5 0

200

400

600

0 0

100

400

400

50

200

200

0 0

200

400

0 0

500

200

400

600

Curved Highway Road

S Road

Hook Road Y - Position (m)

3

40

0 0

Double Lane Change

1000

0 0

500

1000

X - Position (m)

Fig. 10: Road Courses used for controller simulations

Simulations are carried out in MATLAB/SIMULINK software using Heun ODE2 solver with fixed step size of 0.001 s. The proposed adaptive controller is applied on the validated armoured 17

vehicle model as explained in Section 2 with constant speed of 6 m/s, where the vehicle is assumed to enter the trajectory with the initial 6 m/s speed and kept at the constant speed with zero throttle, brake setting, and firing force. The controller performance was compared against basic controllers without adaptive algorithm, namely original Stanley controller (St) as proposed by Hoffmann, et al. [16], and shown in Eq. (20) and the Modified Stanley controller (Mod St) from Eq.(22). In order to display controller’s validity under different inputs, the adaptive controller was simulated through series of tests using different trajectories and speeds. Few speeds are chosen from different area within knowledge database range. In terms of the steering capabilities, the steering output is saturated at ±10 deg in both directions, considering the limitation of the system. Also, this is the region in which the steering system controller has been tested on with satisfactory performance in terms of accuracy and delay. In simulating the controller’s behaviour to navigate these courses, the non-adaptive controllers, namely St Controller and Mod St Controller are tuned to have optimum performance using Particle Swarm Optimisation (PSO) for each trajectory and a constant speed of 6 m/s. The tuned controller parameter values are listed in Table 7. Table 7: Controller parameters for St and Mod St Controllers for each trajectory

St Straight Multiple Lane Change Double Lane Change Hook S Curve

Mod-St

k

k1

k



k

10 10 10 10 10 10

10 10 10 10 10 10

10 10 9.689 10 9.757 10

-2.964 0.3046 0.0901 0.0423 0.0642 0.1762

0.7719 1.892 0.819 -0.058 0.0199 -0.0051

4.2 Simulation Results Series of simulations have been carried out to test the developed controller and evaluate its effectiveness on different road courses and speed values. Six road courses as explained in Section 4.1 are used to represent different types of road courses for the armoured vehicle. In order to evaluate the adaptive controller’s performance, lateral error between vehicle and desired trajectory is observed and compared against the original Stanley Controller and the base controller without adaptive strategy, namely Modified Stanley Controller (Mod St). The following graphs show these comparisons for each of the six road courses for Straight, Multiple Lane Change, Double Lane Change, Hook, S, and Curve roads, respectively.

18

Lateral Error for Straight Road

Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

Y - Position (m )

60 40

L ateral E rro r (m )

Straight Road

1

20

0.5 2 4 6

0 0

50

100 150 200 X - Position (m)

250

0.05

0.2

0 -0.05 0

0.1

Adaptive St RMS = 3.79e-02 Mod St RMS = 4.01e-02 St RMS = 3.07e-02

10 20

0

-0.1 0

300

Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

0.3

50

100 150 200 X - Position (m)

(a)

250

300

(b)

Fig. 11: Trajectory tracking performance for Straight road: (a) Vehicle trajectories, (b) Lateral Error, e

Vehicle Trajectories

Lateral Error Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

4

5.9 5.8

2

546 548 550 552 554

0

-2

Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

-4 0

200

400 X - Position (m)

Lateral Error (m )

6

0.05

0

-0.05 0

Adaptive St RMS = 4.90e-03 Mod St RMS = 2.94e-03 St RMS = 1.48e-02

200

600

400 X - Position (m)

(a)

600

(b)

Fig. 12: Trajectory tracking performance for Multiple Lane Change road: (a) Vehicle trajectories, (b) Lateral Error, e

Lateral Error

Vehicle Trajectories

-3

Y - P o s itio n (m )

3

x 10

Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

L a tera l E rro r (m )

Y - P o sitio n (m )

6

2 3.44 3.42 3.4 3.38 3.36 360

1 0 0

200

0.01

6 0 -2 260

320

0

-0.01 -0.02

365

400 X - Position (m) (a)

0.02

Adaptive St RMS = 7.54e-04 Mod St RMS = 7.99e-04 St RMS = 6.17e-03

600

-0.03 0

Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

200

400 X - Position (m)

600

(b)

Fig. 13: Trajectory tracking performance for Double Lane Change road: (a) Vehicle trajectories, (b) Lateral Error, e

19

100

Lateral Error 0.3

Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

L ate ral E rro r (m )

Y - P o sitio n (m )

Vehicle Trajectories Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

0.2

58.4

50

0.1

58.3 58.2 341.2 341.3 341.4

0 0

Adaptive St RMS = 8.97e-03 Mod St RMS = 2.59e-03 St RMS = 1.42e-01

100

200 300 X - Position (m)

0 0

400

100

200 300 X - Position (m)

(a)

400

(b)

Fig. 14: Trajectory tracking performance for Hook road: (a) Vehicle trajectories, (b) Lateral Error, e

Vehicle Trajectories

Lateral Error

500

Y - P o sitio n (m )

Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

400

231.48

Lateral Error (m )

0.4 0.3

231.44

300

Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

0.2

480.996

231.5

Adaptive St RMS = 9.71e-03 Mod St RMS = 6.29e-03 St RMS = 1.70e-01

481.008

0.1

200 231.2

100

480.98

0 0

200

481.04

400 600 800 X - Position (m)

0 0

1000

200

400 600 800 X - Position (m)

(a)

1000

(b)

Fig. 15: Trajectory tracking performance for S road: (a) Vehicle trajectories, (b) Lateral Error, e

Vehicle Trajectories

Y - P o s itio n (m )

Trajectory Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

400 300

180.9

200 100

180.7 440.4

0 0

200

180.784

180.772 440.445

440.465

Mod St RMS = 6.26e-03 St RMS = 1.85e-01

0.2 0

-0.2

440.8

400 600 800 X - Position (m) (a)

Lateral Error 0.4 Adaptive St RMS = 1.11e-02

Lateral Error (m )

500

1000

0

Stanley Controller with Fuzzy Supervisor Modified Stanley Controller (Mod St) Basic Stanley Controller

200

400 600 800 X - Position (m)

1000

(b)

Fig. 16: Trajectory tracking performance for Curved Highway road: (a) Vehicle trajectories, (b) Lateral Error, e

Going through simulation results for the six roads from Fig. 11 to Fig. 16, it can be seen that the adaptive controller managed to successfully guide the vehicle along all the six trajectories. From the six courses, the first three courses, namely straight, multiple lane change, and double lane 20

change represent shorter roads of below 1 km range and sharp cornering manoeuvres, while the last three roads represent smooth cornering with large curvature roads and longer range of more than 1 km. Regardless of the road conditions, the adaptive mechanism with Fuzzy supervisor has been successful in automatically tune the controller to follow various trajectories with 6 m/s constant speed, recording lateral error of below 0.1 m. This indicate the controller’s ability to navigate various turning and manoeuvrings. However, one can clearly see the significant difference between the three controllers’ performances. For all trajectories, the adaptive controller recorded a superior performance over the original Stanley. This can be attributed to the adaptive capability of the proposed controller which can anticipate the curvature and adjust the controller’s parameters. The controller also has three terms with four tune-able parameters that makes it more sensitive to these changes, and the consideration of the yaw rate error makes the controller to behave more efficiently. Differently, the original Stanley only has one fixed parameters which were tuned to have general performance. Also, the absence of yaw rate feedback caused the controller unable to anticipate the trajectory better in determining steering command. When compared against the base controller, Modified Stanley (Mod St) which has no adaptive capability, the proposed adaptive controller can be seen to perform poorer, relatively. The difference is visible in the lateral error graphs which show that Mod St Controller has lower error throughout courses as well as the RMS values. This observation is crucial in order to study the effect of integrating the adaptive mechanism to the base controller. In understanding the poorer performance of the adaptive controller, one should bear in mind that the Mod St Controller has been optimised properly using Particle Swarm Optimisation for each trajectory and the specific speed value of 6 m/s. Each road course has different set of controller parameters which contribute to the exceptional performance recorded by the base controller. While it can be preferable to have lower error, the effort to tune and optimise the four controller parameters for each road course and vehicle speed can be rigorous, and one should be adopting a more general method which can cater various driving conditions. Overall RMS values for lateral error is listed in Table 8 which shows 16 – 94% improvement recorded by the proposed adaptive controller when compared against basic Stanley Controller. Table 8: Comparison of RMS values for lateral error between the proposed Adaptive Stanley Controller, Modified Stanley Controller, Mod St, and the original Stanley Controller, St

Straight Multiple Lane Change

Adaptive 5.93E-02 4.90E-03

Mod St 5.43E-02 2.94E-03

St 7.13E-02 1.48E-02

% Diff w.r.t. Mod St 8.43 40.00

% Diff w.r.t. St -16.83 -66.89

Double Lane Change Hook S Curved

7.54E-04 8.97E-03 9.71E-03 1.11E-02

7.99E-04 2.59E-03 6.29E-03 6.26E-03

6.17E-03 1.42E-01 1.70E-01 1.85E-01

-5.97 71.13 35.22 43.60

-87.78 -93.68 -94.29 -94.00

21

Another aspect of the adaptive controller is that it can cater various vehicle speeds. To investigate this, the adaptive controller was implemented on the vehicle model and the same manoeuvrings were simulated with various vehicle speed. Random speeds were chosen for analysis which does not correspond to the fixed interval in knowledge database. Also, boundary speed which is 20 m/s was also chosen to observe the controller’s performance at maximum speed. Simulation results for four of the six roads are presented in Fig. 17. It can be seen clearly that the vehicle was steered along the courses successfully. This indicates the ability of the controller to adapt to various vehicle speed. The performance is quantified with the RMS values of lateral error as shown in Table 9 which indicates that the average error throughout the courses are well below 0.7 m. Vehicle Trajectories for Different Speed

6

Vehicle Trajectories for Different Speed Y - P o s itio n (m )

Y - P o sitio n (m )

4.2

4 2 3.4

0

400

410

Trajectory V = 8 m/s V = 12 m/s V = 17 m/s V = 20 m/s V = 30 m/s

420

-2 -4 0

100

200

300 400 500 X - Position (m)

600

3

3.46 3.44

2

3.42 3.4 3.38 360 365 370

1 0 0

700

Trajectory V = 8 m/s V = 12 m/s V = 17 m/s V = 20 m/s

100

200

300 400 500 X - Position (m)

(a)

(b)

50

500

Y - P o s itio n (m )

Y - P o sitio n (m )

100

400

27.2

300

Trajectory V = 8 m/s V = 12 m/s V = 17 m/s V = 20 m/s

323

322

200

26.6 300.4

700

Vehicle Trajectories for Different Speed

Vehicle Trajectories for Different Speed Trajectory V = 8 m/s V = 12 m/s V = 17 m/s V = 20 m/s

600

301.2

553.98

554

100

0 0

100

200 X - Position (m)

300

400

0 0

200

400 600 800 X - Position (m)

1000

(c) (d) Fig. 17: Effect of varying speed for (a) Multiple Lane Change road, (b) Double Lane Change road, and (c) Hook road (d) Curved Highway road Table 9: RMS values of Lateral Error for various vehicle speed under the Adaptive Controller

Road Course

Vehicle Constant Speed (m/s) 8

12

17

20

Straight

0.1365 m

0.3347 m

0.4800 m

0.5824 m

MLC

0.0084 m

0.0189 m

0.0433 m

0.0723 m

DLC

0.0017 m

0.0040 m

0.0098 m

0.0142 m

Hook

0.0597 m

0.1189 m

0.3298 m

0.5013 m

S

0.0689 m

0.1383 m

0.3981 m

0.5948 m

22

Curve

0.0747 m

0.1515 m

0.4291 m

0.6372 m

5 Validation of Steering Angle Against Human Driver 5.1 Experimental Validation Procedures To validate the proposed adaptive controller, an experiment has been conducted involving an instrumented armoured vehicle driven by a human driver along an actual road. The driving data was recorded in terms of steering input from the human driver. The same road was used in simulation where the controller will guide the armoured vehicle model along simulated road. Resulted steering input generated by the adaptive controller during the simulated manoeuvring is compared against the human driver’s input, as well as the resulted vehicle trajectories. By this, one can observe the difference between human’s driver and controller in navigating the road. The main aim of the experiment is to record data for comparison between simulated manoeuvring from the controller and actual manoeuvring by human driver. From this, two main observations can be made. First, the controller’s ability in imitating human driver’s behaviour to navigate the road can be evaluated. Also, controller’s performance in guiding the armoured vehicle along an actual road can be evaluated. The armoured vehicle instrumented prototype is shown in Fig. 18. Various sensors were installed to observe vehicle state such as linear and angular accelerations, speed, as well as position. In addition, a rotary encoder is used to record the steering column’s rotation to indicate the steering input from human driver. From this, wheel angle can be determined using relationship between steering column angle and wheel angle which has been calibrated earlier. Also, a DC motor is installed to actuate the steering system based on controller’s command. However, actuation is not involved in this procedure since this procedure only require driving data from sensors. All sensors are integrated and interfaced using IMC DAQ which is connected to a computer for data storage and display. The IMC DAQ unit also comes with a built-in GPS to record vehicle latitude and longitude data. In unwanted cases where the GPS should fail, vehicle’s position can be obtained using Eq. (19) and vehicle data obtained from the sensors. Specifically, full sensors, actuators, and data logger used on the armoured vehicle are listed and described in Table 10. Configuration of the sensors and integration with IMC DAQ can be shown in Fig. 18 (b). Table 10: Equipment installed on armoured vehicle prototype

Equipment Tri-axis accelerometer sensor Tri-axis gyro sensor Speed sensor

Function Measure vehicle body acceleration on COG in lateral (x), longitudinal (y), and vertical (z) directions Measure Yaw, Pitch and Roll response

Brand G Force Jacobs Design (Aust) Pt. Ltd.

Measure vehicle longitudinal speed

Rotary encoders IMC DAQ

Measure steering column rotation angle Interfacing hardware and software for data logging Measure vehicle position in terms of latitude and

Doppler radar DRS 100 of GMH Engineering E40S 8 5000 3 N24 IMC Cronos Compact CRC400-13 Built in with IMC DAQ

GPS Unit

3 Force Jacobs Design (Aust)

23

DC C Motor

longitude Provide aactuation signnal to steeringg actuator

VEXTA B Brushless Mootor (100 Watt) B BLH5100K-115 GF

(a) (b) Fig. 188: (a) Prototypee of armoured veehicle and (b) Sensors S configurration in driverr’s cockpit.

With the instrumennted vehiclee, driving tests are condducted as beenchmark. T The vehiclee is human driven, and the steeering actioons are recoorded for comparison with controoller action from the proposeed steering control c law. The test is conducted with 20 km//h speed to match the ssimulation studies done with the same speed s previoously. Alsoo, previous studies andd implemenntations of autonom mous vehiclles have beeen recordedd to operate with aboutt 10 m/s (366 km/h) or llower [17, 53, 54]. The samee road in exxperiment iis simulatedd on the arrmoured veehicle modeel and the proposeed adaptive Stanley coontroller as proposed inn previous section. Thhe simulatedd steering actions and vehiclee performancce in navigaating these rroads are coompared agaainst the expperimental results. The acttual road chhosen for thhis experim ment is on thhe vicinity of Nationall Defence U University Malaysiia (UPNM). The road is recordedd as series oof latitude aand longitudde points thhrough the GPS sennsor onboarrd during thhe experimeent. Fig. 19 shows the UPNM rooad used annd vehicle trajectorry (red line)) from coorddinate data recorded. T The series off coordinatees then convverted into series of X-Y pointts using Greeat Circle D Distance theeory [55, 566] and haversine formuula [57] to determinne the distance betweenn each poinnt and a fixed origin. Grreat Circle D Distance theeory states that thee shortest ddistance bettween two points on a sphere is the lengthh of the strraight line connectting these points. Howeever, there is no straigght line on a sphere. Thherefore, the distance can be ddetermined using the arc a length off great circlles on the sphere. Greaat circle is a circle on the spheere with an origin that coincides c w with the origgin of the spphere. By asssuming the earth as a perfect sphere, thiss theory cann be used w where all thhe longitudee lines are great circlees and the equator line is thee only latituude great ccircle. By ccalculating the t distancee on the grreat circle (“Great Circle Disttance”), onee can determ mine the disstance betw ween two points on eartth surface. To calcculate the ggreat circlee distance, haversine formula is commonlyy used and “remains particulaarly well-conditioned for numeriical compuutation evenn at small distances” [55]. The haversinne formula iis shown in shown in E Eq. (28).     s  RE  2 aarcsin  sinn 2    2  

  2    co os  cos  s sin   1 2      2    

(28)

24

F Fig. 19: Road uused and actuall reading for vehhicle trajectory during experim ment

mine distance between any a point to origin. By notating thee origin as Eq. (28)) is then useed to determ Point 1 and other aarbitrary poiint as Point 2, s is the ddirect distannce betweenn the two pooints in m, RE is thhe radius oof earth, 6..3711 106 m m,  1 and  2 are Latittude 1 andd 2 respectiively, and pectively. All A latitude  and  are thee differencee between ttwo latitudees and longitudes, resp and longgitude calcuulations are in rad. Theese points aare then useed as the pree-defined paath during simulatiion as show wn in Fig. 221. The origgin is chosenn to be the initial posittion for vehiicle and X and Y distances d arre the lateraal (with resspect to inittial latitude direction) and transveerse (with respect to initial loongitude dirrection) disttance betweeen each pooint and thee origin, resspectively. Thus, X and Y disttances (sx aand sy) for eeach point is i obtained as illustrateed in Fig. 20. Upon obtaininng the set oof points, a smooth traajectory linee should bee constructeed to producce a good manoeuuvring. To ddo this, thee points aree fitted intoo a radial arc a equationn to producce smooth curvaturre lines witth less polyygonal featuures. This w will ensure smoother m manoeuvrinngs by the simulateed controlleer. The convverted roadss are shown in Fig. 21 for the curvvature road from Fig. 19. Thiss road is thhen used in the simulattion to obseerve the conntroller actioons in naviggating the road com mpared to hhuman respoonses.

25

Fig. 20: C Converting latituude and longitudde data to globaal coordinates

Desired Traajectory in Global G Coordiinates Y - Position (m )

0 -50

-100 -150 -200 0

50

100 150 200 X - Positio on (m)

2 250

300

Fig. 21: C Converted X-Y pooints for pre-def efined trajectoryy in simulation

5.2 Experimentaal Results wo behaviouurs are observed, whichh are the vehhicle trajectoories and whheel angle For this analysis, tw generateed throughoout manoeuvvring whilee navigatingg defined road as descrribed in Fig. 19 with constantt speed of 220 km/h. The T results are shown in Fig. 222 where actuual data froom human driving are comparred against results r from m simulation using the pproposed adaaptive contrroller with Fuzzy suupervisor. From F graph (a), one cann observe thhe trajectoryy for the arm moured vehicle during experim ment and sim mulation, w which indicaates that thee proposed controller managed too generate automattic steering input in guiiding the arrmoured vehhicle along ddesired trajeectory. Disccrepancies betweenn the results are mainly attributed tto variationss in vehicle speed. In thhe experimeent, human instinct has causedd the driver to slow doown the vehhicle, while constant sppeed of 20 km/h was used thrroughout sim mulation. Meanwhhile, observving the whheel angle ggenerated fr from graph (b), compaarison betweeen wheel angle generated g byy human aand the conntroller can be seen. T The controller providees similar steeringg input as human h driveer in terms of trends, bbut with fasster actions. Further obbservation from R RMS values of both innputs shownn that the adaptive coontroller m managed to guide the 26

armoured vehicle with lower steering input compared to human driver. 25% difference were recorded for the adaptive controller’s input when compared to human driver’s inputs. This shows that the proposed controller managed to follow desired trajectory while mimicking the same trend of human input with lower average magnitude. Vehicle Trajectory in Global Coordinates Y - P o s itio n (m )

Y - P o sitio n (m )

-50

-100 -150 -200 0

Desired Trajectory Human Driver Adaptive - Fuzzy 50

100 150 200 X - Position (m)

250

Wheel Angle

15

0

300

10 5

Human Driver Adaptive - Fuzzy

0 -5 RMS Human = 5.3031

-10 RMS Adaptive (Fuzzy) = 4.0260 -15 0 50 100 150 200 X - Position (m)

250

300

(a) (b) Fig. 22: Comparison between experimental results and simulation for (a) Vehicle trajectory (b) Steering input required

6 Conclusions In this paper, a study on an adaptive controller for an unmanned armoured vehicle is presented. Overall, the general conclusion for this paper can be summarised as follows:  

 



A nonlinear mathematical model for the armoured vehicle used in this study has been presented briefly as proposed previously by Aparow, et al. [35]. An adaptive controller based on a Modified Stanley control law with a Fuzzy Inference System as parameter supervisor has been developed from an optimal knowledge database. The controller was aimed to enable the armoured vehicle to navigate various road trajectories with various speed settings. Simulation results have been presented, showing the ability of the proposed controller in navigating different trajectories as well as adapting to different vehicle speed. This shows 16 – 94% improvement compared to the original Stanley Controller. Steering input generated by the controller was compared against human driver input from experimental navigation with an instrumented armoured vehicle. It was shown that the controller managed to generate correctional wheel angle that was similar to ones provided by human driver. The proposed adaptive controller with Gain Scheduling algorithm has been proven to perform satisfactorily in navigating road courses and adapting to various road trajectories and vehicle speeds.

The paper starts with description of a verified armoured vehicle model based on previous studies by authors. This model includes a 7 DOF vehicle model in longitudinal plane, integrated with tyre model to calculate the longitudinal and lateral tyre forces, powertrain model to determine the traction torque by engine, load distribution model to determine the vertical forces, and slip equations to estimate the tyre slip angle and longitudinal slip, and a kinematic model to determine the vehicle’s position with respect to global coordinate axes. The vehicle is also equipped with a pitman arm steering system which is modelled as a transfer function and 27

electronically actuated with a DC motor. The model is then used to develop an adaptive trajectory tracking controller with a Fuzzy supervisor based on a knowledge database. Development of the controller is presented in this paper where the knowledge database is built using Particle Swarm Optimisation. A Fuzzy inference system is then developed based on the database to automatically adjust controller parameters depending on vehicle speed and heading error between vehicle and trajectory directions. This enable the controller to adapt to various trajectories as well as vehicle speed which will keep on changing throughout manoeuvring. The proposed controller is evaluated through series of simulations on six different trajectories. Based on the results, the proposed adaptive controller performed well in guiding the armoured vehicle along various trajectories with lateral error below 0.1 m. Compared against the Stanley (St) controller, the adaptive controller performed better with a much lower error throughout the trajectories. Meanwhile, compared against the non-adaptive base controller (Mod St), the controller performed slightly poorer since the Mod St controller has been tuned specifically for the particular trajectory and speed whereas the adaptive controller is automatically tuned using the Fuzzy supervisory algorithm without the need of any tuning effort. The adaptive controller was also shown to be able to adapt to various vehicle speed though series of simulations. Satisfactory lateral errors were recorded for all trajectories and speeds with understandably higher errors for maximum speed of 20 m/s (72 km/h). Nevertheless, the RMS values for lateral errors were well kept at below 0.7 m. From the experimental validation, steering correction angle that was generated from the controller agrees well with the experimental data from human driver. Overall, it can be concluded that the proposed controller is a viable solution for trajectory tracking controller to be implemented on an unmanned armoured vehicle.

Acknowledgement The authors would like to thank the Malaysian Ministry of Education through research grants LRGS (LRGS/B-U/2013/UPNM/DEFENCE & SECURITY-P1). References [1]

[2]

[3]

[4]

N. H. Amer, H. Zamzuri, K. Hudha, and Z. A. Kadir, "Modelling and Control Strategies in Path Tracking Control for Autonomous Ground Vehicles: A Review of State of the Art and Challenges," Journal of Intelligent & Robotic Systems, vol. 86, pp. 225-254, 2017. A. L. Rankin, C. D. Crane Iii, D. G. Armstrong Ii, A. D. Nease, and H. E. Brown, "Autonomous path-planning navigation system for site characterization," in Navigation and Control Technologies for Unmanned System, Orlando, Florida, USA, 1996, pp. 176186. M. J. Barton, "Controller Development and Implementation for Path Planning and Following in an Autonomous Urban Vehicle," BEng Bachelor's Thesis, Australian Centre for Field Robotics (ACFR), School of Aerospace, Mechanical and Mechatronic Engineering, The University of Sydney, 2001. M. Elbanhawi, M. Simic, and R. Jazar, "The Role of Path Continuity in Lateral Vehicle Control," Procedia Computer Science, vol. 60, pp. 1289-1298, 2015.

28

[5]

[6]

[7]

[8] [9]

[10]

[11]

[12]

[13]

[14]

[15] [16]

[17]

[18]

[19]

[20]

G. V. Raffo, G. K. Gomes, J. E. Normey-Rico, C. R. Kelber, and L. B. Becker, "A Predictive Controller for Autonomous Vehicle Path Tracking," IEEE Transactions on Intelligent Transportation Systems, vol. 10, pp. 92-102, 2009. D.-H. Kim, C.-S. Han, and J. Y. Lee, "Sensor-based motion planning for path tracking and obstacle avoidance of robotic vehicles with nonholonomic constraints," Proceedings of the Institution of Mechanical Engineers, Part C: Journal of Mechanical Engineering Science, p. 0954406212446900, 2012. G. Bayar, M. Bergerman, A. B. Koku, and E. i. Konukseven, "Localization and control of an autonomous orchard vehicle," Computers and Electronics in Agriculture, vol. 115, pp. 118-128, 2015. S. Kato, E. Takeuchi, Y. Ishiguro, Y. Ninomiya, K. Takeda, and T. Hamada, "An Open Approach to Autonomous Vehicles," IEEE Micro, vol. 35, pp. 60-68, 2015. S. F. Campbell, "Steering control of an autonomous ground vehicle with application to the DARPA urban challenge," MSc Master's Thesis, Massachusetts Institute of Technology, 2007. Y. Kanayama, Y. Kimura, F. Miyazaki, and T. Noguchi, "A stable tracking control method for an autonomous mobile robot," in IEEE International Conference on Robotics and Automation Cincinnati, Ohio, USA, 1990, pp. 384-389 vol.1. Z. Sun, Q. Chen, Y. Nie, D. Liu, and H. He, "Ribbon Model based path tracking method for autonomous land vehicle," in 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vilamoura, Portugal, 2012, pp. 1220-1226. G. Scaglia, E. Serrano, A. Rosales, and P. Albertos, "Linear interpolation based controller design for trajectory tracking under uncertainties: Application to mobile robots," Control Engineering Practice, vol. 45, pp. 123-132, 2015. M. A. Zakaria, H. Zamzuri, R. Mamat, and S. A. Mazlan, "A Path Tracking Algorithm Using Future Prediction Control with Spike Detection for an Autonomous Vehicle Robot," International Journal of Advanced Robotic Systems, vol. 10, 2013. Y. Kuwata, J. Teo, S. Karaman, G. Fiore, E. Frazzoli, and J. P. How, "Motion planning in complex environments using closed-loop prediction," in AIAA Guidance, Navigation, and Control Conference and Exhibit, Honolulu, Hawaii, 2008, p. 7166. M. Buehler, K. Iagnemma, and S. Singh, The 2005 DARPA grand challenge: the great robot race vol. 36: Springer Science & Business Media, 2007. G. M. Hoffmann, C. J. Tomlin, D. Montemerlo, and S. Thrun, "Autonomous Automobile Trajectory Tracking for Off-Road Driving: Controller Design, Experimental Validation and Racing," in American Control Conference, New York, USA, 2007, pp. 2296-2301. S. Thrun, M. Montemerlo, H. Dahlkamp, D. Stavens, A. Aron, J. Diebel, et al., "Stanley: The robot that won the DARPA Grand Challenge," Journal of Field Robotics, vol. 23, pp. 661-692, 2006. O. Töro, T. Bécsi, and S. Aradi, "Design of Lane Keeping Algorithm of Autonomous Vehicle," Periodica Polytechnica Transportation Engineering, vol. 44, pp. 60-68, 2016 2016. J. M. Snider, "Automatic Steering Methods for Autonomous Automobile Path Tracking," Robotics Institute, Carnegie Mellon University, Technical Report CMU-RI-TR-90-17, 2009. N. H. Amer, K. Hudha, H. Zamzuri, V. R. Aparow, Z. A. Kadir, and A. F. Z. Abidin, "Hardware-in-the-Loop Simulation of Trajectory Following Control for a Light 29

[21]

[22]

[23]

[24] [25]

[26]

[27]

[28] [29]

[30]

[31] [32]

[33]

[34]

Armoured Vehicle Optimised with Particle Swarm Optimisation," International Journal of Heavy Vehicle Systems vol. "In Press", pp. 1-25, 2017. M. Sathiyanarayanan, S. Azharuddin, and S. Kumar, "Four Different Modes To Control Unmanned Ground Vehicle For Military Purpose," International Journal of Engineering Development and Research, vol. 2, pp. 3156-3166, 2014. B. Paden, M. Cap, S. Z. Yong, D. Yershov, and E. Frazzoli, "A Survey of Motion Planning and Control Techniques for Self-driving Urban Vehicles," IEEE Transactions on Intelligent Vehicles, vol. 1, pp. 33-55, 2016. J. Fei and C. Lu, "Adaptive Sliding Mode Control of Dynamic Systems Using Double Loop Recurrent Neural Network Structure," IEEE Transactions on Neural Networks and Learning Systems, vol. PP, pp. 1-12, 2018. J. Fei and C. Lu, "Adaptive fractional order sliding mode controller with neural estimator," Journal of the Franklin Institute, 2018/02/01/ 2018. Y. Chu, J. Fei, and S. Hou, "Dynamic global proportional integral derivative sliding mode control using radial basis function neural compensator for three-phase active power filter," Transactions of the Institute of Measurement and Control, vol. 0, p. 0142331217726955, 2017. H. Wang, G. I. Mustafa, and Y. Tian, "Model-free fractional-order sliding mode control for an active vehicle suspension system," Advances in Engineering Software, vol. 115, pp. 452-461, 2018. X. Li, Z. Wang, J. Zhu, and Q. Chen, "Adaptive tracking control for wheeled mobile robots with unknown skidding," in IEEE Conference on Control Applications (CCA), Sydney, NSW, Australia, 2015, pp. 1674-1679. E. Lucet, R. Lenain, and C. Grand, "Dynamic path tracking control of a vehicle on slippery terrain," Control Engineering Practice, vol. 42, pp. 60-73, 2015. P. S. Pratama, J. H. Jeong, S. K. Jeong, H. K. Kim, H. S. Kim, T. K. Yeu, et al., "Adaptive Backstepping Control Design for Trajectory Tracking of Automatic Guided Vehicles," in AETA 2015: Recent Advances in Electrical Engineering and Related Sciences, H. V. Duy, T. T. Dao, I. Zelinka, H.-S. Choi, and M. Chadli, Eds., ed Cham: Springer International Publishing, 2016, pp. 589-602. S. Hima, B. Lusseti, B. Vanholme, S. Glaser, and S. Mammar, "Trajectory tracking for highly automated passenger vehicles," in International Federation of Automatic Control (IFAC) World Congress, Milan, Italy, 2011, pp. 12958-12963. M. A. Zakaria, "Trajectory Tracking Algorithm for Autonomous Ground Vehicle," PhD PHD Thesis, Universiti Teknologi Malaysia, 2015. Y. Shan, W. Yang, C. Chen, J. Zhou, L. Zheng, and B. Li, "CF-Pursuit: A Pursuit Method with a Clothoid Fitting and a Fuzzy Controller for Autonomous Vehicles," International Journal of Advanced Robotic Systems, vol. 12, pp. 1-13, 2015. Z. Zheng and L. Sun, "Adaptive sliding mode trajectory tracking control of robotic airships with parametric uncertainty and wind disturbance," Journal of the Franklin Institute, vol. 355, pp. 106-122, 2018/01/01/ 2018. Z. A. Kadir, S. A. Mazlan, H. Zamzuri, K. Hudha, and N. H. Amer, "Adaptive Fuzzy-PI Control for Active Front Steering System of Armoured Vehicles: Outer Loop Control Design for Firing On The Move System," Strojniški vestnik-Journal of Mechanical Engineering, vol. 61, pp. 187-195, 2015.

30

[35]

[36]

[37]

[38]

[39]

[40]

[41] [42] [43]

[44]

[45] [46]

[47]

[48]

[49]

V. R. Aparow, K. Hudha, M. M. H. M. Ahmad, and H. Jamaluddin, "Development and Verification of 9-DOF Armored Vehicle Model in the Lateral and Longitudinal Directions," Jurnal Teknologi, vol. 78, pp. 117–137, 2016. Z. A. Kadir, K. Hudha, H. Zamzuri, S. A. Mazlan, M. Murrad, and F. Imaduddin, "Modeling, validation and firing-on-the-move control of armored vehicles using active front-wheel steering," The Journal of Defense Modeling and Simulation, vol. 13, pp. 253267, 2016. G. Genta, Motor vehicle dynamics: modeling and simulation (series on advances in mathematics for applied sciences) vol. 43. Covent Garden, London: World Scientific Publishing Co. Pte. Ltd, 1997. V. R. Aparow, K. Hudha, Z. A. Kadir, N. H. Amer, S. Abdullah, and M. M. H. Megat Ahmad, "Identification of an optimum control algorithm to reject unwanted yaw effect on wheeled armored vehicle due to the recoil force," Advances in Mechanical Engineering, vol. 9, pp. 1-16, 2017/01/01 2016. K. Hudha, Z. A. Kadir, and H. Jamaluddin, "Simulation and experimental evaluations on the performance of pneumatically actuated active roll control suspension system for improving vehicle lateral dynamics performance," International Journal of Vehicle Design, vol. 64, pp. 72-100, 2014. V. R. Aparow, F. Ahmad, K. Hudha, and H. Jamaluddin, "Modelling and PID control of antilock braking system with wheel slip reduction to improve braking performance," International Journal of Vehicle Safety, vol. 6, pp. 265-296, 2013. E. Bakker, L. Nyborg, and H. B. Pacejka, "Tyre modelling for use in vehicle dynamics studies," Society of Automotive Engineers, Technical Paper1987. H. Pacejka, Tire and vehicle dynamics. Oxford: Elsevier, 2006. E. P. Ping, K. Hudha, and H. Jamaluddin, "Hardware-in-the-loop simulation of automatic steering control for lanekeeping manoeuvre: outer-loop and inner-loop control design," International journal of vehicle safety, vol. 5, pp. 35-59, 2010. M. Short, M. Pont, and Q. Huang, "Simulation of Vehicle Longitudinal Dynamics," University of Leicester, Embedded Systems Laboratory, Technical Report ESL 04-01, 2004. J. Y. Wong, Theory of ground vehicles: John Wiley & Sons, 2001. J. Wang, J. Steiber, and B. Surampudi, "Autonomous ground vehicle control system for high-speed and safe operation," in American Control Conference, 2008, Seattle, Washington, USA, 2008, pp. 218-223. N. H. Amer, H. Zamzuri, K. Hudha, V. R. Aparow, Z. A. Kadir, and A. F. Z. Abidin, "Modelling and trajectory following of an armoured vehicle," in 2016 SICE International Symposium on Control Systems (ISCS), Nagoya, Japan, 2016, pp. 1-6. N. H. Amer, H. Zamzuri, K. Hudha, V. R. Aparow, Z. A. Kadir, and A. F. Z. Abidin, "Path tracking controller of an autonomous armoured vehicle using modified Stanley controller optimized with particle swarm optimization," Journal of the Brazilian Society of Mechanical Sciences and Engineering, vol. 40, p. 104, January 31 2018. R. C. Eberhart and J. Kennedy, "A new optimizer using particle swarm theory," in Proceedings of the sixth international symposium on micro machine and human science, New York, USA, 1995, pp. 39-43.

31

[50]

[51] [52]

[53] [54] [55]

[56] [57]

L. X. Wang, "Stable adaptive fuzzy controllers with application to inverted pendulum tracking," IEEE Transactions on Systems, Man, and Cybernetics. Part B, Cybernetics, vol. 26, pp. 677-691, 1996. L. X. Wang, Adaptive fuzzy systems and control: Design and stability analysis: PrenticeHall, Inc., 1994. E. P. Ping, K. Hudha, M. H. B. Harun, and H. Jamaluddin, "Hardware-in-the-loop simulation of automatic steering control: Outer-loop and inner-loop control design," in 11th International Conference on Control Automation Robotics & Vision (ICARCV), Singapore, 2010, pp. 964-969. M. Buehler, K. Iagnemma, and S. Singh, The DARPA urban challenge: autonomous vehicles in city traffic vol. 56: springer, 2009. X. Wang, M. Fu, H. Ma, and Y. Yang, "Lateral control of autonomous vehicles based on fuzzy logic," Control Engineering Practice, vol. 34, pp. 1-17, 2015. C. Veness. (2010, Dec 22). Calculate Distance And Bearing Between Two Latitude/Longitude Points Using Haversine Formula In Javascript. Available: http://www.movable-type.co.uk/scripts/latlong.html C. H. Pearson. (2013, Dec. 22). Latitude, Longitude, And Great Circles. Available: http://www.cpearson.com/excel/LatLong.aspx R. Sinnott, "Virtues of the Haversine," Sky and Telescope, vol. 68, p. 158, 1984.

32

Noor H Hafizah Am mer receiveed her firsst degree, M MEng (Honns) in Mecchanical Enngineering (Autom motive) from m The University of Notttingham, UK U and MEnngSc in Mecchanical Enngineering, Universsiti Malaya, Malaysia. She is curreently attachhed as an accademic stafff with the Universiti Pertahannan Nasionaal Malaysiaa (UPNM) aand pursuingg her PhD inn Universitii Teknologii Malaysia (UTM). Her reseearch intereests includde vehicle control syystem, autoomotive suuspension, optimisaation and auutonomous vvehicle.

Khisbullah Hudh ha receivedd his BEngg in Mechaanical Desiign from B Bandung Innstitute of Technollogy (ITB), Indonesia; MSc in the Departmeent of Enginneering Prooduction Deesign from Technissche Hoogeschool Utreecht at Nethherlands andd his PhD iin Intelligennt Vehicle Dynamics Control using Maggnetorheoloogical Dampper from U Universiti T Teknologi M Malaysia (U UTM). His researchh interests iinclude moodelling, ideentification and force tracking coontrol of seemi-active damper,, evaluationn of vehiclee ride and handling, h ellectronic chhassis controol system ddesign and intelligeent control. He is currently attachhed as Assoociate Profeessor with U Universiti P Pertahanan Nasionaal Malaysia (UPNM) and a activelyy involved in i parallel hybrid h vehiicle and acttive safety system for f military armoured vehicle. v

Hairi Z Zamzuri is aan Academiic Staff in U Universiti Teknologi T M Malaysia (UT TM). He recceived his BEng inn Control Syystem from UTM, Mastter of Electrrical Engineeering at thee same univeersity, and PhD in the field off Artificial Intelligencee and Contrrol Design from Loughhborough U University. His reseearch intereest is on integrated vehhicle dynam mic control aand active ssafety technnology for ground vehicles. C Currently, hheading a rresearch labb under coollaborationn between U UTM and National carr manufacturrer. Perusahhaan Otomobbil Nasionall Sdn Bhd (Proton), a N

Vimal R Rau Aparoow receivedd his BEng aand MSc inn the Departtment of Auutomotive, Faculty F of Mechannical Engineeering, Techhnical Univeersity of Maalaysia Mallacca (UTeM M). Currenttly, he is a graduatee research assistant and a a Ph.D candidate in Mechannical Enginneering (Auutomotive) Departm ment in Natiional Defense Universitty of Malayysia (UPNM M). His reseaarch primarily focuses on activve safety sysstem for military armouured vehiclee, active braaking sytem m and hybridd vehicles. His receent researchh interests innclude in veehicle modeling, brake modeling, ssystem idenntifications and inteelligent conttrol system for f the vehicle active saafety system m.

Amar Faiz F Zainall Abidin recceived his first f degree, MEng (Hoons) in Electtrical and Electronics E Engineeering from T The Universsity of Nottiingham, Maalaysia and M MEng from Universiti T Teknologi Malaysiia (UTM). He is currrently attachhed as an academic sstaff with U Universiti T Teknologi MARA,, Pasir Gudaang, Malayssia. His reseearch intereests multi-obbjective opttimisation annd natureinspiredd optimisatioon algorithm ms.

Zulkifflli Abd Kad dir received his BEng aand MSc in tthe Departm ment of Autoomotive Enngineering, Universsiti Teknikal Malaysia Melaka. Hiis research interests incclude tyre m modelling, eevaluation of vehicle dynamiics and conntrol. He iis currentlyy attached with the U Universiti P Pertahanan Nasionaal Malaysiaa and activvely involvved in vehiicle modeliing, system m identificaations and intelligeent control system s for thhe vehicle aactive safetyy system.

Muham mad Murrad received hhis BE, ME E and PhD ffrom Univerrsiti Teknoloogi Malaysiia (UTM). He was commissiooned into thee Malaysiann Army in 1981. He haas had widee range of rregimental logisticss experience and held a variety oof commandd positions in areas including: Coommander Light Aid A Detachm ment of Arrtillery Schoool, Officerr-in-Commaand 34th A Armoured R Regimental Workshhop and Coommanding Officer 733rd Divisionnal Workshhop. He alsso held varrious staff positionns in areas inncluding: E EME Staff O Officer 12th Infantry Brrigade, EME E Staff Offiicer Grade One 2ndd Infantry Division, D E Engineering Staff Officcer Grade O One of Policcy Divisionn, Defence Logisticcs Departm ment in Minnistry of D Defence, Malaysia M andd currently seconded from the Malaysiian Armed F Forces to thhe Universitti Pertahanann Nasional Malaysia (U UPNM). Hiis research interestss include arm moured vehhicle vibratioons and dynnamics modeelling.

Research Highlights 

An adaptive steering controller for an autonomous armoured vehicle is developed using Fuzzy Inference System and an optimum knowledge database optimised using PSO;



Development of the controller is using a non-linear vehicle model to ensure the simulated vehicle response to be as close as possible to real conditions and accurate parameter tuning;



Vehicle speed and heading error, which are related to the turning curvature and vehicle slips, are chosen for the adaptive input. This is to increase the controller’s ability in adapting to various manoeuvring conditions;



Modified Stanley controller is used as the base controller due to its simple and proven ability.



The validation experimental setups and procedure is presented to verify the controller ability in generating realistic steering command compared against human driver.



Simulation results show the ability of the proposed controller in navigating different trajectories as well as adapting to different vehicle speed with 16 – 94% improvement compared to the original Stanley Controller.



Steering input generated by the controller showed that the controller managed to generate correctional wheel angle that was similar to ones provided by human driver.