The goals of this project are:
- 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.
- Define what parameters constitute the state.
- Discuss how values for time horizon was arrived at sampling duration.
- Describe how waypoints are followed.
Project Video |
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:
- Sum of squared cross track
cte
and anglular velocityespi
errors and difference between velocity and reference velocity - Sum of squared actuator inputs (
delta
anda
) (akin to regularization) - Sum of squared actuator differences from one time step to the next (from
t
tot+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.
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.
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).
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
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.
-
cmake >= 3.5
-
All OSes: click here for installation instructions
-
make >= 4.1(mac, linux), 3.81(Windows)
- Linux: make is installed by default on most Linux distros
- Mac: install Xcode command line tools to get make
- Windows: Click here for installation instructions
-
gcc/g++ >= 5.4
- Linux: gcc / g++ is installed by default on most Linux distros
- Mac: same deal as make - [install Xcode command line tools]((https://developer.apple.com/xcode/features/)
- Windows: recommend using MinGW
-
- Run either
install-mac.sh
orinstall-ubuntu.sh
. - If you install from source, checkout to commit
e94b6e1
, i.e.Some function signatures have changed in v0.14.x. See this PR for more details.git clone https://github.com/uWebSockets/uWebSockets cd uWebSockets git checkout e94b6e1
- Run either
-
Ipopt and CppAD: Please refer to this document for installation instructions.
-
Eigen. This is already part of the repo so you shouldn't have to worry about it.
-
Simulator. You can download these from the releases tab.
-
Not a dependency but read the DATA.md for a description of the data sent back from the simulator.
- Clone this repo.
- Make a build directory:
mkdir build && cd build
- Compile:
cmake .. && make
- Run it:
./mpc
.