10
This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/ This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEE Transactions on Intelligent Vehicles T-IV-2020-0514 1 Real-time Implementation of Randomized Model Predictive Control for Autonomous Driving Arun Muraleedharan, Hiroyuki Okuda and Tatsuya Suzuki Abstract—Model predictive control (MPC) using randomized optimization is expected to solve different control problems. How- ever, it still faces various challenges for real-world applications. This paper attempts to solve those challenges and demonstrates a successful implementation of randomized MPC on the au- tonomous driving using a radio-controlled (RC) car. First of all, a sample generation technique in the frequency domain is discussed. This prevents undesirable randomness which affect the smoothness of the steering operation. Second, the proposed randomized MPC is implemented on a Graphics Processing Unit (GPU). The expected GPU acceleration in calculation speed at various problem sizes is also presented. The results show the improved control performance and computational speed that was not achievable using CPU based implementation. Besides, the selection of parameters for randomized MPC is discussed. The usefulness of the proposed scheme is demonstrated by both simulation and experiments. In the experiments, a 1/10 model RC car is used for collision avoidance task by autonomous driving. Index Terms—Autonomous vehicles, model predictive control, sampling based optimization, Graphics Processing Unit (GPU). I. I NTRODUCTION M ODEL Predictive Control (MPC) [1]–[3] is a popular control method for multi-variable constrained control problems. Although MPC had first appeared in [4] published in the 1960s, the major growth in its application emerged later as the result of the improvements in computational resources. The model in MPC stands for the underlying model representing the dynamics of the system being controlled. This model enables future prediction of the controlled system. In addition, MPC observes the state at each control cycle. This makes the system tolerant of environmental changes in real-time. Motion control is a problem that has been difficult to handle in real-time. It is, however, well addressed by MPC due to its above-mentioned advantages. Autonomous driving has positioned itself in the difficult end of motion control problems. Being highly dynamic and safety-critical, it requires the calculation of accurate control inputs in real- time. The computation involved within the MPC to solve the model-based optimization problem has been challenging in real-time implementations. One of the ideas to overcome the Manuscript received May 14,2020. This work was not supported by any organization. A.Muraleedharan is with the Department of Mechanical Systems Engineer- ing, Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e- mail: [email protected]) H.Okuda is with the Department of Mechanical Science and Engineering, Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e- mail: h [email protected]) T.Suzuki is with the Department of Mechanical Systems Engineering, Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e- mail: t [email protected]) computational complexity is a sampling based MPC called Randomized MPC (RMPC) [5]–[10] that enables us to balance computational demands at the expense of accuracy. Regardless of its simplicity in implementation, RMPC explores the global solution space and perform strict constraint satisfaction checks in every iteration. The infinite horizon stability and optimality of RMPC are proven in [5] and [7], respectively. Lack of an index of optimality and being semi-optimal at the same time remains to be a challenge in RMPC application. On the other hand, behavior control of an autonomous vehicle can be seen as two distinct tasks- path planning and path following. They are executed alternately. Planning has to be repeated since the planner has to consider constraints on safety such as collision avoidance and speed limitation. This is in addition to the basic target of path planning for keeping a lane, overtaking, etc. Many path planning schemes have been well demonstrated in robotics and automotive applications as seen in [11]–[14]. Considering that the car has an updated path that is planned, the next step is to follow it accurately. For accurate path following, a controller needs to observe the present state of the car and provide correct steering and acceleration inputs. There have also been many works on path following [1]–[3], [15], [16]. Path following control could be performed using various control strategies such as proportional–integral–derivative (PID) control, state feedback controllers, MPC, and so on. Having the path planning and tracking as two different processes is a popular method in the literature. Considering vehicle dynamics constraints in both stages separately implies that such consideration becomes un- necessarily redundant. Combining these two into one problem formulation clearly has the benefit of a lower computational burden by removing redundancies in vehicle dynamics cal- culations. Such combined problems are often referred to as simultaneous motion planning and control (SMPLC) problem [17]–[19]. During the studies on SMPLC by the authors in [17] and [18], real-time implementation of SMPLC was found to be facing various challenges. The major challenge was due to the computational complexity in solving an SMPLC problem. Some notable examples that had demonstrated real time steer- ing control with non-linear MPC are [3] and [20]. The work [3] has reported an average computation time, which is over 150 ms, limiting their stable experiment speed at 7m/s. While, [20] demonstrates an average processing time of 60ms (with pre- calculated invariant sets), enabling multiple obstacle avoidance at a speed of 14m/s. Both [3] and [20] show obstacle avoidance while driving on a straight road. The strict real-time limits associated with a safety-critical problem like autonomous

Real-time Implementation of Randomized Model Predictive

  • Upload
    others

  • View
    5

  • Download
    0

Embed Size (px)

Citation preview

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 1

Real-time Implementation of Randomized ModelPredictive Control for Autonomous Driving

Arun Muraleedharan, Hiroyuki Okuda and Tatsuya Suzuki

Abstract—Model predictive control (MPC) using randomizedoptimization is expected to solve different control problems. How-ever, it still faces various challenges for real-world applications.This paper attempts to solve those challenges and demonstratesa successful implementation of randomized MPC on the au-tonomous driving using a radio-controlled (RC) car. First ofall, a sample generation technique in the frequency domain isdiscussed. This prevents undesirable randomness which affectthe smoothness of the steering operation. Second, the proposedrandomized MPC is implemented on a Graphics Processing Unit(GPU). The expected GPU acceleration in calculation speed atvarious problem sizes is also presented. The results show theimproved control performance and computational speed thatwas not achievable using CPU based implementation. Besides,the selection of parameters for randomized MPC is discussed.The usefulness of the proposed scheme is demonstrated by bothsimulation and experiments. In the experiments, a 1/10 model RCcar is used for collision avoidance task by autonomous driving.

Index Terms—Autonomous vehicles, model predictive control,sampling based optimization, Graphics Processing Unit (GPU).

I. INTRODUCTION

MODEL Predictive Control (MPC) [1]–[3] is a popularcontrol method for multi-variable constrained control

problems. Although MPC had first appeared in [4] publishedin the 1960s, the major growth in its application emergedlater as the result of the improvements in computationalresources. The model in MPC stands for the underlying modelrepresenting the dynamics of the system being controlled.This model enables future prediction of the controlled system.In addition, MPC observes the state at each control cycle.This makes the system tolerant of environmental changes inreal-time. Motion control is a problem that has been difficultto handle in real-time. It is, however, well addressed byMPC due to its above-mentioned advantages. Autonomousdriving has positioned itself in the difficult end of motioncontrol problems. Being highly dynamic and safety-critical,it requires the calculation of accurate control inputs in real-time. The computation involved within the MPC to solve themodel-based optimization problem has been challenging inreal-time implementations. One of the ideas to overcome the

Manuscript received May 14,2020. This work was not supported by anyorganization.

A.Muraleedharan is with the Department of Mechanical Systems Engineer-ing, Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e-mail: [email protected])

H.Okuda is with the Department of Mechanical Science and Engineering,Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e-mail: h [email protected])

T.Suzuki is with the Department of Mechanical Systems Engineering,Nagoya University, Furo cho, Chikusa ku, Nagoya, Japan, 464-8603 (e-mail: t [email protected])

computational complexity is a sampling based MPC calledRandomized MPC (RMPC) [5]–[10] that enables us to balancecomputational demands at the expense of accuracy. Regardlessof its simplicity in implementation, RMPC explores the globalsolution space and perform strict constraint satisfaction checksin every iteration. The infinite horizon stability and optimalityof RMPC are proven in [5] and [7], respectively. Lack of anindex of optimality and being semi-optimal at the same timeremains to be a challenge in RMPC application.

On the other hand, behavior control of an autonomousvehicle can be seen as two distinct tasks- path planning andpath following. They are executed alternately. Planning has tobe repeated since the planner has to consider constraints onsafety such as collision avoidance and speed limitation. Thisis in addition to the basic target of path planning for keeping alane, overtaking, etc. Many path planning schemes have beenwell demonstrated in robotics and automotive applications asseen in [11]–[14]. Considering that the car has an updatedpath that is planned, the next step is to follow it accurately.For accurate path following, a controller needs to observethe present state of the car and provide correct steering andacceleration inputs. There have also been many works onpath following [1]–[3], [15], [16]. Path following controlcould be performed using various control strategies such asproportional–integral–derivative (PID) control, state feedbackcontrollers, MPC, and so on. Having the path planning andtracking as two different processes is a popular method in theliterature. Considering vehicle dynamics constraints in bothstages separately implies that such consideration becomes un-necessarily redundant. Combining these two into one problemformulation clearly has the benefit of a lower computationalburden by removing redundancies in vehicle dynamics cal-culations. Such combined problems are often referred to assimultaneous motion planning and control (SMPLC) problem[17]–[19].

During the studies on SMPLC by the authors in [17] and[18], real-time implementation of SMPLC was found to befacing various challenges. The major challenge was due tothe computational complexity in solving an SMPLC problem.Some notable examples that had demonstrated real time steer-ing control with non-linear MPC are [3] and [20]. The work [3]has reported an average computation time, which is over 150ms, limiting their stable experiment speed at 7m/s. While, [20]demonstrates an average processing time of 60ms (with pre-calculated invariant sets), enabling multiple obstacle avoidanceat a speed of 14m/s. Both [3] and [20] show obstacle avoidancewhile driving on a straight road. The strict real-time limitsassociated with a safety-critical problem like autonomous

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 2

driving made it difficult to find an optimal solution in real-time. Even sampling-based optimization schemes like RMPCcould not be realized in necessary control frequency withtraditional CPU based implementation. During the simulationstudy of RMPC for vehicle control, another issue was alsonoticed. The randomness in the sampling step was found togive a negative impact on the smoothness of the car which isbeing driven. This will be more emphasized when the RMPCis applied to passenger vehicles rather than autonomous robots.This necessitates a need for a smoothing technique in thesampling phase so that the control action remains smooth.

By taking a deeper look at the RMPC framework, theobserver would notice its inherent nature of parallelism. Thesequence of processes like series creation and calculation ofcost could be performed on all sample points simultaneously.This interesting feature of RMPC can directly be linked tothe parallel processing feature of a Graphics Processing Unit(GPU). At present, every application that contains abundantparallelism is showing interest in GPUs. GPUs are of interestdue to their significantly larger computational throughput incomparison to the CPUs, which are built for higher latency.This gives GPU’s a tremendous potential to improve thecomputational speed of applications with massive parallelism[21].

Previous works on sampling based MPC can be dividedinto two categories. The first category is the developmentof the sampling based solver for MPC [5], [22], [23]. Thesecond one is the study focusing on the implementation ofSampling based MPC [24]–[28]. In the first category, [22]developed a method that searches the control space by seedinga tree from the previous best sample and expanding it in amanner similar to rapidly exploring random tree (RRT). Thepaper [5] suggested a sampling based MPC for one-leg robotnavigation using a potential field representation of obstacles.Even though implementation is not the focus of this work, theauthors claimed that they could improve performance only atthe expense of computational load. The paper [23] applied amodified version of RMPC to the drive of high-speed RC cars,which enabled faster real-time computation.

In the second category, the control of a drinking waternetwork is addressed in [24]. Since the network is largeand contains multiple controllable elements, a GPU basedimplementation was suggested. Although the problem size islarge, this application adopted longer control intervals thanthe case of controlling a car due to its slow dynamics. In[25], the authors successfully controlled a mobile robot forobstacle avoidance using an embedded GPU. Here the robotdynamics were considered as a point mass model and the robotspeed was extremely low. Different approaches for nonlinearmodel predictive control that runs on GPU can be seen inpapers [26] and [27]. The optimization algorithms used werenot sampling based in nature and the application domain wasmuch different from the control of an autonomous vehicle.Finally, in the survey paper [28], a summary of variousparallel implementations of MPC was described. This paperpresents a detailed discussion of the present challenges thatMPC faces and how parallel computation helps to solve thosechallenges. This paper concludes that the majority of GPU

based implementations are faster in doing calculations, butsuffer from a high overhead of memory transfer time andkernel creation time. Once combining the time of overheadsand calculation, any improvement over the CPU case is notsignificant at regular use cases.

Since none of the previous works directly addressed au-tonomous driving with RMPC, we have studied the feasibilityof the RMPC for autonomous driving. The paper [17] hasimplemented obstacle avoidance driving of a car using RMPCin simulation. This paper suggested some ideas to smoothenthe randomness by sampling in the frequency domain. Thisidea showed smoother steering input, however, the controllerwas restricted to straight line driving at a constant speed. Also,the effectiveness was verified only in simulation with pre-calculated inputs. In addition, the ego car being representedwith a bicycle model, this study concluded that more compu-tational power is necessary to use the RMPC in real-time. Thisdemand for computational improvement was also investigatedin our previous works [29] and [30]. Computation speed oflinear MPC problems was accelerated using GPU in [29],however, this was limited to linear MPC problems. On theother hand, [30] discussed some preliminary results showingthe GPU’s potential to accelerate RMPC. This study was alsolimited to simulations and to straight line driving at constantspeed.

Based on these considerations, this paper addresses theRMPC as a solution for autonomous driving control. First,it extends the previous works [17] and [30] with an improvedvehicle model, thereby removing the limitations of drivingonly in straight line and with a constant speed. Then, it solvesthe problem of randomness by frequency domain samplingand implements the RMPC along with the new samplingmethodology. Second, the proposed RMPC with frequencydomain sampling is implemented on GPU. In-order to transferthe algorithm to GPU, each sample is processed by a differentGPU thread at the same time. With this higher computationalpower, RMPC can process a larger number of samples or evenconsider a longer prediction horizon in strict real-time limits.The presented idea of GPU implementation eliminates theneed for transferring large data between GPU and CPU. Thismethod also keeps the kernel creation overhead to a minimumby not splitting the MPC into subproblems. This solves theissues of time overheads that are typically present in GPUbased implementations [28]. Third, a novel method of step-by-step parameter selection for RMPC is suggested. Simulationsand experiments demonstrate how this new sampling methodcombined with the realization by GPU improves the controlperformance. The validity of the proposed ideas is demon-strated by using a 1:10 RC car that has the same kinematicsas a normal road car.

Attending existing bottlenecks faced by RMPC and demon-strating its potential as a fast and easy-to-implement controller,this work becomes promising for the future of autonomousdriving. Although our target is autonomous driving control,the presented ideas of RMPC, frequency-domain samplingand GPU implementation can be powerful tools for otherapplications, particularly, fast real-time mechanical systemscontrol.

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 3

Fig. 1. Target environment

II. PROBLEM SETTING

A. Task description

In-order to demonstrate RMPC and its improvements, acollision avoidance task as shown in Fig. 1 is chosen. There isan ego car controlled by the controller following a pre-definedreference path xre f . The reference path, expressed in a localcoordinate frame attached to the car (Σl(t)) as seen in Fig. 2is defined as follows [29];

lχre f (t) = {l pre f ,i(t)|i = 0,1, · · · ,Np} (1)

l pre f ,i(t) = {lxpre f ,i(t),

lypre f ,i(t)}. (2)

Here, l χre f (t) is the reference path at time t, it contains Np pathnodes l pre f ,i(t), where l pre f ,i(t) denotes the relative positionof the path node, lxp

re f ,i(t) and lypre f ,i(t), from the car’s origin.

Here the deviation of the car from the reference path, ye(t),is computed as the distance from the car to Op(t), the originof the path coordinate frame Σp(t) at the time of t, which iscomputed by applying the suitable interpolation between pathnodes. The car ideally should drive along the center-line ofthis 6m wide path. It starts at the point (dego

re f (t = 0),ye(t =0),θe(t = 0)) = (0,0,0), which is the origin. Variable t is thetime index, dego

re f represents the distance covered by ego caralong the reference path and ye, θe represent lateral error andyaw error of ego car from the reference path. The car shouldalso make necessary steering maneuver not to collide with theL parked cars on both sides of the street whose position isrepresented by (oi

re f ,oie), i ∈ {1,2, · · · ,L} for the ith parked

car. The controller controls the ego car motion by providingspeed and steering angle commands.

This problem setting is approached as a simultaneous mo-tion planning and control(SMPLC) Problem. The controller isan MPC with the necessary constraints. Since SMPLC unifiesthe planning and tracking into one problem considering theconstraints and car dynamic model, there is no need to plan apath first and then follow it for obstacle avoidance.

In order to represent the dynamics of the car, an equiva-lent bicycle model (sectionII-B) is used. The previous worksthat implemented MPC for navigation using GPU [25] haveadopted a point-mass model for simplifying the problem. Dueto the higher speed of motion, an equivalent bicycle modelis of choice. To keep a safe distance from the obstacles andthe sidewalls, this framework utilizes some input and safetyconstraints as shown in section II-C.

For reliable real-time performance, sample-based approachis chosen to solve the nonlinear optimization problem. The

TABLE IDEFINITION OF PARAMETERS AND VARIABLES

C f Cornering stiffness - Front tire N/radCr Cornering stiffness - Rear tire N/radm Mass of the vehicle kgIz Yaw moment of inertia kgm2

l f Distance from gravity to front axis mlr Distance from gravity to rear axis mδ Steering angle radV Forward velocity of vehicle (const.) m/sρ Curvature of reference path 1/m

Fig. 2. Approximate bicycle model of the car.

sample-based method used in this work is known as RMPC,and is attracting increased attention recently.

Random sampling based methods often lead to randomvariations in the control input. This is not recommended forsmoothness critical tasks like driving. The author’s previouswork [17] indicates some preliminary results indicating asignificant advantage of sampling from the frequency domainfor smooth driving control. In [17], an Inverse Discrete CosineTransform (IDCT) was used in the sample generation processfrom frequency domain. We demonstrate the IDCT methodbeing executed in a GPU and driving our RC car smoothly.

B. State space equation for car dynamics

The vehicle behavior in this paper is assumed to be repre-sented by an approximate bicycle model with its coordinatesystem along the reference path (Fig. 2). The state equationof this model is expressed as follows [31].

[ ˙lvYr

]=

−a11lvX

a12lvX− lvX

− a21lvX l

a22lvX

[ lvYr

]+

[b1b2

]δ , (3)

where

a11 = (C f +Cr)/m, a12 =−(l fC f − lrCr)/m,

a21 = (l fC f − lrCr)/Iz, a22 =−(l2fC f + l2

r Cr)/Iz,

b1 =C f m, b2 = l fC f /Iz.

where lvX and lvY represents the longitudinal and the lateralvelocity in local coordinate frame, respectively. Please refer toTable I for other variables. We further transform the nonlinearstate equation that is given above into an approximate bicycle

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 4

model with it’s coordinate system along the reference path.With the assumption of vehicle speed V being constant withinprediction horizon , the slip angle of the vehicle β and θe tobe small enough, the dynamics of the lateral tracking error yeand the angle θe are summarized as follows (discretized withEuler’s Method):

x(k+1) = Ad(k)x(k)+Bd(k)ut(k)+Wd(k)ρ(k), (4)y(k) =Cx(k), (5)

x(k) =[

ye(k) ye(k) θe(k) θe(k) δ (k)]T (6)

ut(k) = δ∗(k) (7)

Ad(k) =

1 ∆t 0 0 00 1− a11

V (k)∆t a11∆t a12V (k)∆t b1∆t

0 0 1 ∆t 00 − a21

V (k)∆t a21∆t 1+ a22V (k)∆t b2

0 0 0 0 1−α∆t

(8)

Bd(k) =[

0 0 0 0 ∆t]T (9)

Wd(k) =[

0 (a12−V 2(k))∆t 0 a22∆t 0]T (10)

C =

[1 0 0 0 00 0 1 0 0

]. (11)

Where ρ represents the curvature of the reference path at thenearest point and δ ∗ represents the tire angle reference. Actualtire angle δ is considered to have a first order delay from δ ∗

to represent physical delay in steering system. Readers arereferred to our previous work [29] for further details.

C. Input and safety constraints

There are two constraints in this formulation, one is the hardconstraint to ensure feasible input commands and the other oneis to prevent entry into the prohibited area.

The range of control input ut and its rate of change ∆ut areconstrained as follows to maintain physical limits of steeringsystem and to prevent urgent steering action, respectively.

| ut | < 0.1745 (≈ 10 [degrees]) (12)

| ∆ut | < 0.35 radians/sec (≈ 20 [degrees/sec]) (13)

For each parked car, an ellipse around them defines theprohibited area with a safety margin. This area for ith parkedcar is expressed by an inequality(

degore f (t)−oi

re f

ria

)2

+

(ye(t)−oi

e

rib

)2

> 1

∀i ∈ {1,2, · · · ,L} (14)

where L is the number of cars parked, (oire f ,o

ie) is the position

of i th parked car. The length of the major and minor axis ofthe ellipse around ith parked car are ri

a and rib, respectively.

The areas beyond sidewalls are also expressed as prohibitedareas represented with a logarithmic function as explained inthe next subsection (19).

Fig. 3. Potential field of sidewalls.

D. Cost function and reference state

The goal of the controller is to drive the car on the centerof the street, without colliding with the obstacles. On takinga closer look at the given case, it can be seen that the needto follow the street center and to stay away from obstaclesare obviously conflicting. While avoiding obstacles, it is alsoimportant to keep a safe distance from them, than followingthe closest path to the obstacle. This is satisfied by addinga potential field term in the cost function. There are weightparameters to balance between terms to stick to the referencepath and terms to avoid a collision. Finally, another potentialfield is also added to keep a safe distance from the side walls.

The cost function J(ut) for an input series ut =[u(0|t),u(1|t), · · · ,u(N−1|t)] to be optimized at time t is

J(ut) =N−1

∑k=1

s0(k|t)(φ

T (k|t)Qφ(k|t)+∆u(k|t)T R∆u(k|t))

+φT (N|t)Q f φ(N|t)

+Qobs

N−1

∑k=1

s jPj

obs(k|t)+Qwall

N

∑k=1

Pwall(k|t) (15)

where φ(k|t) =y(k|t), (16)∆u(0|t) =0, ∆u(k|t) = |u(k|t)−u(k−1|t)|1

∀k ∈ {1,2, · · · ,N−1}, (17)

where N, φ and ∆u represents prediction horizon length ofMPC, state error and the time difference in control input,respectively. The representation u(k|t) is the value of u atprediction horizon step k at time t. Q = diag(Qye ,Qθe) andR being weight parameters, balance the control performanceto the effort. Q f acts on the last step in the prediction horizonas a penalty to the residue.

This framework enables us to follow any reference pathxre f that we need, the reader can refer to our previous work[29] for a detailed study on the path tracking performance ofthis dynamic model. Further details on the weight parametermatrices and the terms si(k|t), s0(k|t) can be found in author’sprevious work [17]. When the ego car approaches a parkedcar i, the switching parameter si approaches to 1. This makesthe repulsive force more significant. Otherwise, following thereference state is of higher priority.

Qobs and Qwall works as weight parameters for the potentialfield around parked cars and sidewalls. Potential functionaround jth parked car is expressed by P j

ob j:

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 5

P job j(k|t) =C exp

(−(

degore f (k|t)−o j

re f

r ja

)2− (ye(k|t)−o j

e

r jb

)2

)(18)

where [degore f (k|t),ye(k|t)] are the ego car position along refer-

ence path predicted for prediction horizon step k at time t. C,ri

a and rib can adjust potential field area and magnitude. Side

walls have their own potential field Pwall :

Pwall(k|t) =(log |ywl |+ log |ywr|)− (log(ywl− ye(k|t)+ log(ye(k|t)− ywr)) (19)

where ywl = 3,ywr = −3 are side wall locations. Pwall isdesigned to increase steeply close to the walls, as shown infig 3.

E. Formulation of input optimization problem

The optimization problem to be solved in every controlstep in order to generate optimum control input series canbe formulated as follows:

given

x(0|t) = x(t), xre f , (20)

find

u(k|t), (k ∈ {0,1, · · · ,N−1}) (21)

which minimize

J(ut = {u(k|t)}), (k ∈ {0,1,2, · · · ,N−1}) (22)

subject to

Input constraints (12), (13)Prohibited area constraint (14), (19)Car dynamics (4). (23)

III. SEMI OPTIMAL SOLUTION USING SAMPLING INFREQUENCY DOMAIN

The problem in consideration is a non-linear optimizationproblem and it has to be solved in real-time. There are non-linear constraints associated with safe driving and a non-linear vehicle model. Typical methods to find the solution isapproximating the non-linear constraints in some way for thesolvers [23]. This paper tries to eliminate these approximationsby the application of a random sample based approach. Thismethod is proven to provide a semi optimal solution whichis close enough to the optimal solution, once the necessarysample size is considered [7]. The process of this methodof optimization starts with sample generation. Ns number ofsample sequences that are of the length N is picked from aspecific distribution of random numbers. The next step is tocalculate the future trajectory for the car, assuming it followseach of these sample sequences. At this point, some constraintbased filtering is performed to remove the samples that areinfeasible. In the case if majority of the samples are foundto be infeasible, there is threat on safety. In such a case,

the controller should switch to a mode of emergency stop orrequest manual driving. This follows the calculation of the costassociated with each sample according to a cost function. Theminimum cost series is then identified and it’s first elementgoes as the input to the ego car. The controller repeats thesesteps for each control cycle.

A. Sampling in the frequency domain for smoother inputsamples

Generating samples randomly is expected to carry therandomness into the control input as well. Since given controlinput is the steering command to the car, this randomness is notrecommended for smooth driving performance. The suggestedsampling method generates the samples from the frequencydomain. These are then converted into the time domain usingthe process of Inverse Discrete Cosine Transform(IDCT). Fol-lowing this process, it is possible to obtain smoother samplesthat drives the car smoother.

The following set of equations explains the process ofsample generation in detail.

uiIDCT (0|t) = u(t−1) (24)

uiIDCT (k|t) = ui

IDCT (k−1|t)+∆uiIDCT (k|t),

∀k ∈ {1, · · · ,N} (25)

∆uiIDCT (t)

T = γDU iIDCT (t)

T (26)

U iIDCT (l|t)

{∼U (−1,1) if l ≤ Fc/o= 0 other

. (27)

Here, D∈RN×N is the coefficient of IDCT and l is the indexrepresenting the frequency component. Each element of D iscalculated as follows:

Di j =

√2N

ki cos((i−1)( j−1/2)π

N

),

i ∈ {1,2, · · · ,N}, j ∈ {1,2, · · · ,N} (28)

where N is the length of input series. ki (i = 1,2, ...,N) is anormalizing factor that has two values

ki =

1√2

i = 1

1 i 6= 1

. (29)

U iIDCT (t) is sampled from a uniform distribution ranging (-

1,1) in this case. γ is a parameter that can be used to adjust theresulting input rate of change according to (13). Fc/o is a cut-off threshold that prevents higher frequency components in theresulting input sequence. The smaller the Fc/o the smoother inthe resulting input series. Unless specified, an Fc/o of 15 isused in this paper. If any of the element ut generated in (25)is found to violate the constraint (12), a new random numberis generated to replace the U i

IDCT (l|t) until ut satisfies (12).The control performance with and without IDCT can be seenin Fig. 4 (Ns=500). The graphs show visible improvementin control signal smoothness and steering performance. Insummary, the contents of IDCT is essentially random numbergeneration followed by some matrix multiplications and seriesmaking. The following sections will demonstrate how theabove-mentioned operations were efficiently ported to GPU.

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 6

X displacement (m)

Y d

ispla

cem

ent

(m)

(degre

e)

(degre

e)

Ste

ering A

ngle

Yaw

Fig. 4. Control performance with and without IDCT

B. Validation of proposed sampling method

Before using RMPC for real experiments, its performanceis evaluated in simulation-based experiments. Since the ex-periments are performed in a 1:10 scale car, a high fidelitycar simulator is necessary for simulations. Carsim by VirtualMechanics Inc. is used owing to its excellent vehicle andenvironment models. The controller issues an updated controlinput in every control cycle. In the simulation experiments,the control interval dT is set as 0.1 seconds. The predic-tion horizon length is set as N = 50. This means that thecontroller calculates the optimal input considering vehiclebehavior predictions of 5 seconds into the future. The follow-ing combination of parameters resulted in the best possibletracking performance. Q f = 1, Q = diag(10,10), R = 3000,Qobs = 3000 and Qwall = 5, respectively. The parameter γ isset to 1. The parked cars are at the positions o1 = (50,0.85)and o2 = (80,−0.85), respectively. Since the optimizationis based on random samples, there is an obvious questionof its closeness to the global optimum. There have beensome previous works [7] that quantifies the minimum samplesize for the solution to be global with a defined probabilitylevel. Referring to [7], it is calculated that a sample size ofNs > 458 is necessary for the solution to have confidence levelof 99%(αbelieve = 0.01). Hence, the controller is tested at asample size of Ns = 500. Fig. 5 demonstrates the performance.Tracking performance is very accurate without any intrusionto the obstacle area which is prohibited. While the author’sprevious works [17] were limited to the performance of thecontroller at sample sizes less than 500, this paper tries to gobeyond this number. Even though Ns = 500 is sufficient for sat-isfiable performance at the simulation conditions, sample sizesbeyond 500 are found to provide better controller performanceas shown in Fig. 5. The majority of control tasks have multiplecontrol variables and stricter constraints. Such cases wouldclearly demand a higher number of samples to be processedin real-time. Another interesting trend in the case of driving

Fig. 5. Number of samples and controller performance

TABLE IISTEPS IN COMPUTATION

Step Function Equation reference1 Random Number Generation (27)2 IDCT (26)3 Series Generation (25)4 State Matrix Calculation (4)5 Cost Calculation (15)6 Minimization of cost −

is related to driving speed. The faster the car is, the shorterthe control interval has to be. Both these conditions demandhigher computational performance. But due to hardware limits,the sample size Ns < 500 was the limit that a CPU basedimplementation could process in real-time. This limitation incomputation power was also expressed in [17] and [23].

IV. IMPLEMENTATION USING GPUA. Computational steps involved

The process of calculating the optimum control input canbe expressed in a sequence of 6 steps as described by TableII. Once the present state variables are obtained from the car,the controller performs steps 1 to 6. The final step does aminimization of all the samples based on a cost function andcomes up with the best sample sequence. The second elementin this sequence will be the optimum input for the car inthe next step. This will be then sent to the car. This processis repeated in every control cycle. The following subsectionsare dedicated to the detailed contents of these steps and themethods in moving them to support parallel computation usingGPU.

B. CPU baselineIn order to have a better understanding about the im-

provements by parallel computing, The controller was first

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 7

Algorithm 1 Randomized MPC1: for Every time step do2: Generate Ns input samples of length N acc. to 2.3: Initialize state matrix.4: for Sample = 1,2, . . . ,Ns do5: for Length = 1,2, . . . ,N do6: Calculate the extended state matrix acc. to 1.7: end for8: end for9: for Sample = 1,2, . . . ,Ns do

10: for Length = 1,2, . . . ,N do11: Calculate the cost for each sample acc. to 3.12: end for13: end for14: Find minimum cost sample Smin.15: Return second element of Smin as next control input.16: end for

implemented using a CPU based algorithm. The steps areexpressed in Algorithm 1. The CPU used in this study is a2.2GHz Intel Core i5. CPU program uses a random devicefunction of the C++ Numerics library [32] to generate randomnumbers. Please note that the steps from 2 to 5 in Table II areperformed on every element, one element at a time using two’for loops’. First one is a ’for loop’ that index the samplenumber Ns, the second one for the length of the sample N.This makes up Ns×N calls to the CPU one after the other.

C. Code design for GPU

The various steps involved in the MPC algorithm weredivided into 6 discrete steps as seen in Table II. Thesesteps were studied in detail to find possible improvementsby porting to a 2560 core GPU (NVidia GeForce GTX10801.7GHz). The basic difference in hardware of CPUs and GPUsare as visualized in Fig.6 [34]. While a normal CPU hasseveral fast ALUs (Arithmetic Logic Units) sharing commoncache memory and controlled by a common controller, GPUshave thousands of ALUs with individual controller and cachememory. Since all of the ALUs in a GPU can run a threadof operation in parallel, the basic idea of implementation isto assign a sample point to each GPU thread, as shown in inillustrative picture Fig. 7. Random samples are stored in anarray of size Ns×N, same number of GPU threads are alsoassigned as a block of size Ns×N.

The first step of random number generation is performedwith Pseudo-random number generation function in CURANDlibrary [33], which is a part of NVidia’s CUDA library [34].Step 2 that performs the IDCT operation (As seen in (22)) andStep 5 that calculates cost (As seen in (10)), are independent ateach discrete sample points. Being independent, they can useas many GPU threads as the hardware allows simultaneousoperation. Matrix multiplication operations associated withStep 2 can also use the maximum possible capacity of GPU.These steps while using one sample point per GPU threadgives Ns×N times faster computation. The remaining stepsin the computation like Steps 3 and 4 depend on previous

Fig. 6. CPU vs GPU architecture

Fig. 7. GPU implementation image

prediction horizon/series value to compute next. These stepshave to be performed in N steps, calculating all Ns samplesat a given time using Ns number of threads. Even here we getNs times improvement in computational time over CPU.

As described in the survey paper [28], the majority of GPUbased implementations are faster in calculation but suffer froma high overhead of memory transfer time and kernel creationtime. The GPU implementation presented here avoid theseproblems in following ways:• By generating the random numbers within the GPU

memory (step 1 in table II), all the steps of computationare kept within the GPU and its memory. Only the presentstate of the car is transferred to GPU and the optimuminput is sent back.

• Certain problem-parallel approaches in literature splitsthe MPC to smaller problems by dividing the predictionhorizon and assign each section to different GPU kernels.Thanks to the random sample based method, our data-parallel approach does not split the MPC into subprob-lems, limiting the kernel creation time to the minimum.

V. EVALUATION USING RC CAR

Using GPU, we expect to produce the same quality controlsignals as that of CPU with significantly lower computationtime. In the context of controlling a car, this can give multiplebenefits. Previous works based on simulations did not considerthe delays caused by localization, error estimation and com-munication delay. Model errors and various other noises werealso ignored by relying solely on simulations. Hence, extensiveexperiments are conducted using an RC car to demonstrate thecontroller under an environment closer to real situation.

A. Experiment setup

The RC car used is a Tamiya 1:10 scale car as shownin Fig. 8. The car has a ’Raspberry Pi’ computer on-board

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 8

Fig. 8. 1:10 RC car with control board and markers for motion capture

TABLE IIICOST FUNCTION AT DIFFERENT SAMPLE SIZES

Sample Number Cost (×104) Improvement over CPU (%)100 16.30500 13.62 16.4

1000 12.43 23.75000 11.19 31.410000 10.37 36.420000 9.77 40.130000 9.70 40.5

receiving the control PWM signals from the control PC via Wi-Fi. A ROS framework is used for communication. The positionof the car is captured in realtime using a camera-based motioncapture system called ’Motive’. The motion capture systemruns at 200Hz frequency which is more than the maximumcontrol frequency. The prediction horizon length N is chosento be 30 (to predict 3 metres ahead).

B. Advantages of higher control frequency

One of the advantages of faster computation using GPU isto run the controller at a higher frequency. This enables theobstacle avoidance possible at higher speeds than the CPU.Under the condition of N = 30, and minimum Ns of 500,the maximum control frequency using CPU is 30Hz. Thiscontroller is found to work fine at a speed of 3.6 km/h1. But,the CPU based system is found to collide with the obstaclesat a speed of 5.1 km/h. This is due to the fact that CPUbased implementation cannot run at a higher control frequency.GPU was able to run at 200Hz with 1000 samples, The GPUperforms smooth avoidance until 11.5km/h. The details of theexperiment is shown in Fig. 9 and the video [35].

C. Advantages of higher sample sizes

Another advantage of using the higher computation speedis the capability of considering more samples at every controlinterval. As discussed earlier in section III-B, a higher samplenumber is expected to bring the solutions closer to the globaloptimum. In the RC car based tests, the control frequency isset to be 100Hz and the number of samples were increased.The results are indicated in Table III and Fig. 10. At 100Hz,CPU can process only 100 samples in real-time. Using a highernumber of samples in real-time, the GPU based controller canhave lower cost values. Even though the reduction in cost

1In a real car, this correspond to 3.6×10 = 36km/h [36].

Fig. 9. Speed limit comparison

Fig. 10. Sample size comparison

value is low at higher sample sizes, the car behavior is visiblysmoother and maintains better safety distance while driving.

VI. DISCUSSION ON PARAMETER SELECTION FOR RMPC

RMPC controllers are characterized by the samples usedand the frequency at which they are updated. The samplesare characterized by the number of samples Ns and lengthof each sample N. Let us denote the control interval as dT .The selection of these parameters is not as easy as it seemsdue to their relationship with each other. Increasing Ns or Nforces dT to increase. For a fixed N, there could be multiplecombinations of Ns and dT that satisfy computational limits.

The recommended procedure to identify these parametersstarts with the identification of N. N is decided first becauseof it’s unique effect on control behavior. Value of N has to bebounded with both upper and lower limits as seen in Fig. 11.On the other hand, acceptable values of Ns and dT could onlybe bounded on one side, minimum Ns and maximum dT .

N can be identified with a few experiments as demonstratedin Fig. 11. We choose the values for Ns and dT intuitively forthis step. It can be seen that the RC car, while performingthe obstacle avoidance task as explained in Section V, has anoptimal range of prediction horizon length N for best trackingperformance. Here, the best N value was found to be 30 steps.

Once we identify the value of N, it is recommended tochoose the optimal dT corresponding to the speed of thesystem. Rule of thumb is that a car moving at double speedwill cover double the distance in the given time. Hence controlfrequency should also be doubled. It is always recommendedto have some tolerance in the dT value considering thecomputational time slightly varies depending on situation.

After choosing the N and dT , it is recommended thatthe maximum sample number is chosen considering given

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 9

Fig. 11. Controller performance for different prediction horizon lengths

computational resources. This is because the cost function isfound to decrease monotonously as the sample size increasesas seen in table III. This method of selection was employedduring parameter selection for the RC car experiments andsimulations presented in this work.

VII. EXTENSION TO COOPERATION WITH SPEED CONTROLON CURVY ROADS

The simulations and experiments discussed until section VIdeal with a constant speed obstacle avoidance task on a straightroad. Such a task is found to be the best choice to highlightthe effects of various control parameters and computationalspeed on the proposed RMPC controller.

This controller works equally well in any kind of road, evenwith those having tight turns. Fig. 12 demonstrates the egocar maneuvering a tight turn and facing a parked car at theexit of the curve. The control parameters are chosen to matchwith section III-B. The ego car is observed to perform smoothcollision avoidance.

The constant speed assumption is replaced with the additionof a speed controller that slows the car down when highersteering angles are commanded. The input vector (7) becomes

ut(k) = [δ ∗(k),v(k)]T (30)

Where,

v(k) =C f (vavg(k)), vavg(k) =1n

n

∑i=1

v(k− i).

C f is a cubic function of vavg and n = 10. The speed profileduring the collision avoidance is seen to be smooth in Fig.12. The proposed lateral controller being independent, speedcontrol can be easily replaced with any other type of controller.

VIII. CONCLUSIONS

This paper has presented a randomized nonlinear modelpredictive controller for autonomous driving while givingspecial emphasis to obstacle avoidance task. Although thevehicle model and the obstacle constraints have nonlinearity intheir nature, the proposed scheme enabled direct considerationof nonlinear constraints by using a randomized optimizationmethod. Random samples for optimization were generatedfrom the frequency domain using IDCT method. This preventsundesirable oscillation in the control input, which is particu-larly important in the autonomous driving. This paper alsoinvestigated the impact of using GPU for implementation ofrandomized MPC. By using GPU, the real-time performancelimit was extended. A parameter selection methodology for

Fig. 12. Tracking a curved path with speed control

randomized MPC has also been discussed. The proposedscheme and improvements were confirmed in simulation andexperiments using an RC-car. The RC-car experiment hasrealized higher driving speeds and shown better control per-formance compared with CPU based controller. Our proposedimplementation scheme for GPU is available for other types ofcontrol systems which are in need of high control performanceunder nonlinear constraints.

REFERENCES

[1] M.Oshima and M.Ogawa, “Model Predictive Control-I : Basic Principle :history & present status,” Trans. on the Institute of Sys., Cont. and Info.Eng., vol.46, NO.5, 2002

[2] M.Kano and M.Oshima, “Model Predictive Control-II : Linear ModelPredictive Control,” Trans. on the Institute of Sys., Cont. and Info. Eng.,vol.46, NO.7, 2002

[3] P. Falcone, F. Borrelli, J. Asgari, et al., “Predictive Active Steering Controlfor Autonomous Vehicle Systems,” IEEE Trans. on Control Sys. Tech.,Vol.15, No.3, 2007.

[4] C. E. Garcia, D.M. Prett and M. Morari, “Model predictive control:Theory and practice-a survey,” Automatica, 1989.

[5] J. L. Piovesan and H. G. Tanner, “Randomized model predictive controlfor robot navigation,” 2009 IEEE Int’l Conf. on Robotics and Automation,pp. 94–99, 2009.

[6] G. Schildbach, G. C. Calafiore and L. Fagiano, “Randomized Model Pre-dictive Control for Stochastic Linear Systems,” 2012 American ControlConf., pp. 417–422, 2012.

[7] M. Vidyasagar, “Randomized algorithms for robust controller synthesisusing statistical learning theory,” Automatica, Vol. 37, No.10, pp. 1515–1528, 2001.

[8] D. D. Dunlap, E. G. Collins Jr. and C. V. Caldwell, “Sampling BasedModel Predictive Control with Application to Autonomous Vehicle Guid-ance,” 2008 Florida Conf. on Recent Advances in Robotics, 2008.

This work is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 License. For more information, see https://creativecommons.org/licenses/by-nc-nd/4.0/

This article has been accepted for publication in a future issue of this journal, but has not been fully edited. Content may change prior to final publication. Citation information: DOI 10.1109/TIV.2021.3062730, IEEETransactions on Intelligent Vehicles

T-IV-2020-0514 10

[9] G. Ripaccioli, D. Bernardini, S. Di Cairano, A. Bemporad and I.V.Kolmanovsky, “A Stochastic Model Predictive Control Approach forSeries Hybrid Electric Vehicle Power Management,” 2010 AmericanControl Conf., pp. 5844–5849, 2010.

[10] X. Zhang , S. Grammatico, G. Schildbachc, P. Goulart and J. Lygeros,“On the Sample Size of Random Convex Programs with StructuredDependence on the Uncertainty,” Automatica, Vol. 60, pp. 182–188, 2015.

[11] B. Paden, M. Cap, S. Z. Yong, D. Yershov and E. Frazzoli, “A Surveyof Motion Planning and Control Techniques for Self-Driving UrbanVehicles,” IEEE Conf. on Intelligent Transportation Systems, Vol. 1, No.1, pp. 33–55, 2018.

[12] J. P. Laumond, P. E. Jacobs, M. Taix and R. M. Murray, “A motionplanner for nonholonomic mobile robots,” IEEE Trans. on Robo. andAuto., Vol. 10, No. 5, pp. 577–593, 1994.

[13] L. Han, H. Yashiro, H. Tehrani Nik Nejad, Q. H. Do and S. Mita, “Beziercurve based path planning for autonomous vehicle in urban environment,”2010 IEEE Intelligent Vehicles, pp. 1036–1042, 2010

[14] S.M.LaValle, “Rapidly-exploring random trees: A new tool for pathplanning,” Int’l J. of Robotics Research, vol.20, no.5, pp. 378–400, 2001.

[15] S. A. Arogeti and N. Berman, “Path Following of Autonomous Vehiclesin the Presence of Sliding Effects,” in IEEE Trans. on Vehicular Tech.,vol. 61, no. 4, pp. 1481–1492, 2012.

[16] A. Koga, H. Okuda, Y. Tazaki, et al., “Autonomous Lane TrackingReflecting Skilled/Un-skilled Driving Characteristics,” 42th Annu. Conf.of the IEEE Industrial Ele. Soc., pp.3175–3180, 2015.

[17] H. Okuda, Y. Liang and T. Suzuki, ”Sampling Based Predictive Controlwith Frequency Domain Input Sampling for Smooth Collision Avoid-ance*,” 2018 21st International Conference on Intelligent TransportationSystems (ITSC), Maui, HI, 2018, pp. 2426-2431.

[18] H. Okuda, N. Sugie and T. Suzuki, “Real-Time Collision AvoidanceControl Based on Continuation Method for Nonlinear Model PredictiveControl with Safety Constraint,” 2017 Asian Control Conf., pp. 1086–1091, 2017

[19] C. Gotte, M. Keller, C. Hass, K. H. Glander, A. Seewald and T.Bertram, “A model predictive combined planning and control approachfor guidance of automated vehicles,” 2015 IEEE Int’l Conf. on VehicularElectronics and Safety, pp. 69–74, 2015

[20] Gao, Yiqi, Andrew Gray, H. Eric Tseng, and Francesco Borrelli. ”Atube-based robust nonlinear predictive control approach to semi au-tonomous ground vehicles,” Vehicle System Dynamics 52, no. 6, 2014,pp. 802-823.

[21] M. Garland, S. Le Grand, J. Nickolls, J. Anderson, J. Hardwick, S.Morton, E. Phillips, Y. Zhang, V. Volkov, “Parallel computing experienceswith CUDA,” IEEE Micro 28, pp. 13–27, 2008.

[22] A. Brooks, T. Kaupp and A. Makarenko, ”Randomised MPC-basedmotion-planning for mobile robot obstacle avoidance,” 2009 IEEE In-ternational Conference on Robotics and Automation, Kobe, 2009, pp.3962-3967.

[23] J. V. Carrau, A. Liniger, X. Zhang and J. Lygeros, ”Efficient imple-mentation of Randomized MPC for miniature race cars,” 2016 EuropeanControl Conference (ECC), Aalborg, 2016, pp. 957-962.

[24] A. K. Sampathirao, P. Sopasakis, A. Bemporad and P. Panos Patrinos,”GPU-Accelerated Stochastic Predictive Control of Drinking Water Net-works,” IEEE Transactions on Control Systems Technology, vol. 26, no.2, pp. 551-562, March 2018.

[25] Phung, D.K., Herisse, B., Marzat, J. and Bertrand, S., ”Model predictivecontrol for autonomous navigation using embedded graphics processingunit,” IFAC-PapersOnLine, 50(1), pp.11883-11888, 2017.

[26] Gang, Y. and Mingguang, L., 2012, December, ”Acceleration of MPCusing graphic processing unit,” Proceedings of 2nd IEEE InternationalConference on Computer Science and Network Technology (pp. 1001-1004),2012.

[27] Ohyama, S. and Date, H., 2017, December, ”Parallelized nonlinearmodel predictive control on GPU,” 11th IEEE Asian Control Conference(ASCC) (pp. 1620-1625),2017.

[28] Abughalieh, K.M. and Alawneh, S.G., ”A Survey of Parallel Implemen-tations for Model Predictive Control,” IEEE Access, 7, pp.34348-34360,2019.

[29] A. Muraleedharan, H. Okuda, and T. Suzuki, “Path tracking control usingmodel predictive control with on GPU implementation for autonomousdriving,” Journal of Arid Land Studies, vol.28, Issue.S, pp. 163–167,2018.

[30] A. Muraleedharan, H. Okuda and T. Suzuki, ”Improvement of ControlPerformance of Sampling Based Model Predictive Control using GPU,”2019 IEEE Intelligent Vehicles Symposium (IV), Paris, France, 2019, pp.1999-2004.

[31] M. Abe,Vehicle Handling Dynamics -Theory and Application-,Butterworth-Heinemann, 2009

[32] C++, “C++ Numerics Library,”[33] NVIDIA, “NVIDIA CUDA CURAND Library,” 10.2, 2019.[34] NVIDIA, “NVIDIA CUDA C++ PROGRAMMING Guide,” 10.2, 2019.[35] A. Muraleedharan, “Real-time Implementation of Randomized Model

Predictive Control for Autonomous Driving,” April. 27, 2020. [OnlineVideo]. Available: https://youtu.be/Mb-3 PnUdJ8

[36] S. Brennan and A. Alleyne, ”Using a scale testbed: Controller designand evaluation,” in IEEE Control Systems Magazine, vol. 21, no. 3, pp.15-26, June 2001.

Arun Muraleedharan was born in Kerala, India in1993. He received the B.Tech. degree in ProductionEngineering from National Institute of TechnologyCalicut, India in 2014. He received the M.S. degreein Mechanical Systems Engineering from NagoyaUniversity, Japan in 2019. He was a research engi-neer with Honda R&D India Pvt. Ltd. from 2014to 2017. Currently, he is a doctoral student inthe Mechanical Systems Engineering department ofNagoya University, Japan. His work focuses on pathplanning and tracking algorithms for autonomous

driving. Presently, he studies stochastic MPC for autonomous driving in sharedroads. It is his goal to help the smooth transition to autonomous driving whilemaintaining the fun factor of driving. He enjoys riding his motorcycle andplaying percussion in his free time. He is a member of JSAE.

Hiroyuki Okuda was born in Gifu, Japan, in 1982.He received B.E. and M.E. degrees in AdvancedScience and Technology from Toyota TechnologicalInstitute, Japan in 2005 and 2007, respectively. Hereceived a Ph.D. degree in Mechanical Science andEngineering from Nagoya University, Japan in 2010.He was a PD researcher with the CREST, JST from2010 to 2012, and an assistant professor at NagoyaUniversity’s Green Mobility Collaborative ResearchCenter from 2012 to 2016. He was a visiting re-searcher in the Mechanical Engineering Department

of U. C. Berkeley in 2018. Currently, he is an assistant professor in theDepartment of Mechanical Science and Engineering at Nagoya University.His research interests are in the areas of system identification of hybriddynamical system and its application to the modeling and analysis of humanbehavior and human-centered system design of autonomous/human-machinecooperative system. Dr. Okuda is a member of IEEE, IEEJ, SICE, and JSME.

Tatsuya Suzuki Tatsuya Suzuki was born in Aichi,JAPAN, in 1964. He received the B.S., M.S. andPh.D. degrees in Electronic Mechanical Engineeringfrom Nagoya University, JAPAN in 1986, 1988 and1991, respectively. From 1998 to 1999, he was avisiting researcher of the Mechanical EngineeringDepartment of U.C.Berkeley. Currently, he is a Pro-fessor of the Department of Mechanical SystemsEngineering, Executive Director of Global ResearchInstitute for Mobolity in Society (GREMO), NagoyaUniversity. He also has been a Principal Investigator

in JST, CREST in 2013-2019. He won the best paper award in InternationalConference on Autonomic and Autonomous Systems 2017 and the outstandingpaper award in International Conference on Control Automation and Systems2008. He also won the journal paper award from IEEJ, SICE and JSAE in1995, 2009 and 2010, respectively. His current research interests are in theareas of analysis and design of human-centric intelligent mobility systems,and integrated design of transportation and smart grid systems. Dr.Suzuki isa member of the SICE, ISCIE, IEICE, JSAE, RSJ, JSME, IEEJ and IEEE.