Skip to content

Model predictive trajectory#

Abstract#

Model Predictive Trajectory (MPT) calculates the trajectory that meets the following conditions.

  • Kinematically feasible for linear vehicle kinematics model
  • Collision free with obstacles and road boundaries

Conditions for collision free is considered to be not hard constraints but soft constraints. When the optimization failed or the optimized trajectory is not collision free, the output trajectory will be previously generated trajectory.

Trajectory near the ego must be stable, therefore the condition where trajectory points near the ego are the same as previously generated trajectory is considered, and this is the only hard constraints in MPT.

Flowchart#

uml diagram

Vehicle kinematics#

As the following figure, we consider the bicycle kinematics model in the frenet frame to track the reference path. At time step k, we define lateral distance to the reference path, heading angle against the reference path, and steer angle as yk, θk, and δk respectively.

vehicle_error_kinematics

Assuming that the commanded steer angle is δdes,k, the kinematics model in the frenet frame is formulated as follows. We also assume that the steer angle δk is first-order lag to the commanded one.

yk+1=yk+vsinθkdt θk+1=θk+vtanδkLdtκkvcosθkdt δk+1=δkδkδdes,kτdt

Linearization#

Then we linearize these equations. yk and θk are tracking errors, so we assume that those are small enough. Therefore sinθkθk.

Since δk is a steer angle, it is not always small. By using a reference steer angle δref,k calculated by the reference path curvature κk, we express δk with a small value Δδk.

Note that the steer angle δk is within the steer angle limitation δmax. When the reference steer angle δref,k is larger than the steer angle limitation δmax, and δref,k is used to linearize the steer angle, Δδk is Δδk=δδref,k=δmaxδref,k, and the absolute Δδk gets larger. Therefore, we have to apply the steer angle limitation to δref,k as well.

δref,k=clamp(arctan(Lκk),δmax,δmax) δk=δref,k+Δδk, Δδk1 

clamp(v,vmin,vmax) is a function to convert v to be larger than vmin and smaller than vmax.

Using this δref,k, tanδk is linearized as follows.

tanδktanδref,k+{dtanδdδ}|δ=δref,kΔδk =tanδref,k+{dtanδdδ}|δ=δref,k(δref,kδk) =tanδref,kδref,kcos2δref,k+1cos2δref,kδk

One-step state equation#

Based on the linearization, the error kinematics is formulated with the following linear equations,

(yk+1 θk+1)=(1vdt 01)(yk θk)+(0 vdtLcos2δref,k)δk+(0 vtan(δref,k)dtLvδref,kdtLcos2δref,kκkvdt)

which can be formulated as follows with the state x, control input u and some matrices, where x=(yk,θk)

xk+1=Akxk+bkuk+wk

Time-series state equation#

Then, we formulate time-series state equation by concatenating states, control inputs and matrices respectively as

x=Ax0+Bu+w

where

x=(x1T,x2T,x3T,,xn1T)T u=(u0,u1,u2,,un2)T w=(w0T,w1T,w2T,,wn1T)T. 

In detail, each matrices are constructed as follows.

(x1 x2 x3  xn1)=(A0 A1A0 A2A1A0  k=0n1Ak)x0+(B000 A0B0B100 A1A0B0A0B1B20 0 k=0n3AkB0k=0n4AkB1A0Bn3Bn2)(u0 u1 u2  un2)+(I00 A0I00 A1A0A0I0 0 k=0n3Akk=0n4AkA0I)(w0 w1 w2  wn2)

Free-boundary-conditioned time-series state equation#

For path planning which does not start from the current ego pose, x0 should be the design variable of optimization. Therefore, we make u by concatenating x0 and u, and redefine x as follows.

u=(x0T,uT)T x=(x0T,x1T,x2T,,xn1T)T

Then we get the following state equation

x=Bu+w,

which is in detail

(x0 x1 x2 x3  xn1)=(I00 A0B000 A1A0A0B0B100 A2A1A0A1A0B0A0B1B20 0 k=0n1Akk=0n3AkB0k=0n4AkB1A0Bn3Bn2)(x0 u0 u1 u2  un2)+(00 I00 A0I00 A1A0A0I0 0 k=0n3Akk=0n4AkA0I)(w0 w1 w2  wn2).

Objective function#

The objective function for smoothing and tracking is shown as follows, which can be formulated with value function matrices Q,R.

J1(x,u)=wykyk2+wθkθk2+wδkδk2+wδ˙kδ˙k2+wδ¨kδ¨k2 =xTQx+uTRu =uTHu+uTf

As mentioned before, the constraints to be collision free with obstacles and road boundaries are formulated to be soft constraints. Assuming that the lateral distance to the road boundaries or obstacles from the back wheel center, front wheel center, and the point between them are ybase,k,ytop,k,ymid,k respectively, and slack variables for each point are λbase,λtop,λmid, the soft constraints can be formulated as follows.

ybase,k,minλbase,kybase,k(yk)ybase,k,max+λbase,k ytop,k,minλtop,kytop,k(yk)ytop,k,max+λtop,k ymid,k,minλmid,kymid,k(yk)ymid,k,max+λmid,k 0λbase,k 0λtop,k 0λmid,k

Since ybase,k,ytop,k,ymid,k is formulated as a linear function of yk, the objective function for soft constraints is formulated as follows.

J2(λbase,λtop,λmid) =wbasekλbase,k+wmidkλmid,k+wtopkλtop,k

Slack variables are also design variables for optimization. We define a vector v, that concatenates all the design variables.

v=(uTλbaseTλtopTλmidT)T

The summation of these two objective functions is the objective function for the optimization problem.

minvJ(v)=minvJ1(u)+J2(λbase,λtop,λmid)

As mentioned before, we use hard constraints where some trajectory points in front of the ego are the same as the previously generated trajectory points. This hard constraints is formulated as follows.

δk=δkprev(0iNfix)

Finally we transform those objective functions to the following QP problem, and solve it.

minv 12vTHv+fv s.t. blowerAvbupper

Constraints#

Steer angle limitation#

Steer angle has a limitation δmax and δmin. Therefore we add linear inequality equations.

δminδiδmax

Collision free#

To realize collision-free trajectory planning, we have to formulate constraints that the vehicle is inside the road and also does not collide with obstacles in linear equations. For linearity, we implemented some methods to approximate the vehicle shape with a set of circles, that is reliable and easy to implement.

    1. Bicycle Model
    1. Uniform Circles
    1. Fitting Uniform Circles

vehicle_circles

Now we formulate the linear constraints where a set of circles on each trajectory point is collision-free. By using the drivable area, we calculate upper and lower boundaries along reference points, which will be interpolated on any position on the trajectory. NOTE that upper and lower boundary is left and right, respectively.

Assuming that upper and lower boundaries are bl, bu respectively, and r is a radius of a circle, lateral deviation of the circle center y has to be

bl+rybur.

bounds

Based on the following figure, y can be formulated as follows.

y=Lsin(θ+β)+ycosβlsin(γϕa) =Lsinθcosβ+Lcosθsinβ+ycosβlsin(γϕa) Lθcosβ+Lsinβ+ycosβlsin(γϕa)
bl+rλybur+λ.
y=C1x+C2 =C1(Bv+w)+C2 =C1Bv+w+C2

Note that longitudinal position of the circle center and the trajectory point to calculate boundaries are different. But each boundaries are vertical against the trajectory, resulting in less distortion by the longitudinal position difference since road boundaries does not change so much. For example, if the boundaries are not vertical against the trajectory and there is a certain difference of longitudinal position between the circe center and the trajectory point, we can easily guess that there is much more distortion when comparing lateral deviation and boundaries.

Ablk=(C1BOOINref×NrefOO C1BOOIOO OOOIOO)R3Nref×Dv+NcircleNref blower,blk=(blowerC1wC2 bupper+C1w+C2 O)R3Nref bupper,blk=R3Nref

We will explain options for optimization.

L-infinity optimization#

The above formulation is called L2 norm for slack variables. Instead, if we use L-infinity norm where slack variables are shared by enabling l_inf_norm.

Ablk=(C1BINref×Nref C1BI OI)R3Nref×Dv+Nref

Tips for stable trajectory planning#

In order to make the trajectory optimization problem stabler to solve, the boundary constraint which the trajectory footprints should be inside and optimization weights are modified.

Keep minimum boundary width#

The drivable area's width is sometimes smaller than the vehicle width since the behavior module does not consider the width. To realize the stable trajectory optimization, the drivable area's width is guaranteed to be larger than the vehicle width and an additional margin in a rule-based way.

We cannot distinguish the boundary by roads from the boundary by obstacles for avoidance in the motion planner, the drivable area is modified in the following multi steps assuming that lwidth is the vehicle width and lmargin is an additional margin.

keep_minimum_boundary_width

Extend violated boundary#

Avoid sudden steering#

When the obstacle suddenly appears which is determined to avoid by the behavior module, the drivable area's shape just in front of the ego will change, resulting in the sudden steering. To prevent this, the drivable area's shape close to the ego is fixed as previous drivable area's shape.

Assume that vego is the ego velocity, and tfix is the time to fix the forward drivable area's shape.

avoid_sudden_steering

Calculate avoidance cost#

avoidance_cost

Change optimization weights#

r=lerp(wnormalsteer,wavoidancesteer,c) wlat=lerp(wnormallat,wavoidancelat,r) wyaw=lerp(wnormalyaw,wavoidanceyaw,r)

Assume that c is the normalized avoidance cost, wlat is the weight for lateral error, wyaw is the weight for yaw error, and other variables are as follows.

Parameter Type Description
wnormalsteer double weight for steering minimization in normal cases
wavoidancesteer double weight for steering minimization in avoidance cases
wnormallat double weight for lateral error minimization in normal cases
wavoidancelat double weight for lateral error minimization in avoidance cases
wnormalyaw double weight for yaw error minimization in normal cases
wavoidanceyaw double weight for yaw error minimization in avoidance cases