Skip to content

Latest commit

 

History

History
111 lines (81 loc) · 4.97 KB

README.md

File metadata and controls

111 lines (81 loc) · 4.97 KB

Writeup

Udacity - Self-Driving Car NanoDegree

Model Predictive Control Project

The goals of this project are:

  1. To design an MPC (model predictive controller) to control a vehicle in a simulated environment, given the position and velocity information of the vehicle and reference waypoints and velocity to be followed.
  2. Define what parameters constitute the state.
  3. Discuss how values for time horizon was arrived at sampling duration.
  4. Describe how waypoints are followed.

Rubrics

1. Results

Project video
Project Video

2. Implementation

The Model

MPC model is described in MPC.cpp. The model, given the state of the vehicle and a 3rd degree fitted polynomial to the waypoints, predicts a trajectory for the vehicle over a short time horizon (0.5 sec) using a non-linear, constrait optimizer.

The cost function is made up of different parts:

  1. Sum of squared cross track cte and anglular velocity espi errors and difference between velocity and reference velocity
  2. Sum of squared actuator inputs (delta and a) (akin to regularization)
  3. Sum of squared actuator differences from one time step to the next (from t to t+dt)

The above cost function makes sure that not only primary errors cte and epsi are minimized, but the ride is robust and smooth.

The different weightings were found by trail and experimentation.

State

We keep track of vehicles pose (x, y, psi), longitudinal velocity v and errors - cross track error cte and heading angle error epsi. We keep track of errors because they are main componenets in the cost function of the optimizer.

Timestep Length and Elapsed Duration (N & dt)

We chose a small time horizon of 0.5 sec (N=10 steps, dt=0.05 sec). Small value of dt helps turn the vehicle on sharp turns (as the vehicle can keep track of sharper turn rate).

Polynomial Fitting and MPC Preprocessing

We convert the waypoints from the global coordinate system to the vehicle's one (makes it easier to calculate cross track error) by a sequence of translation and rotation with the resultant x-axis pointing in the direction of vehicle's heading. Vehicle state is modified accordingly.

A 3rd degree polynomial is fitted to the waypoints to better track the reference trajectory.

The fitted polynomial coefficients and the state is passed to the optimizer.

Following are the state update equations:

Lf = wheelbase

State:
state = (x, y, phi, v, cte, epsi)

Actuators:
delta = steering
a = accelaration

Pose variables:
x_next = x + v*cos(psi)*dt
y_next = y + v*sin(psi)*dt
psi_next = psi + v/Lf*delta*dt
v_next = v + a*dt

Error variables:
cte = f(x) - y
cte_next = cte + v*sin(epsi)*dt

psi_desired = arctan(f'(x))
epsi = psi - psi_desired
epsi_next = epsi + v/Lf*delta*dt

Model Predictive Control with Latency

There is a latency of 100ms between the actuator input and actual execution. To combat this, we forward the pose of the model by the latency time duration before passing it on to the solver.

Dependencies

Basic Build Instructions

  1. Clone this repo.
  2. Make a build directory: mkdir build && cd build
  3. Compile: cmake .. && make
  4. Run it: ./mpc.