CarND-Controls-MPC
Self-Driving Car Engineer Nanodegree Program
Project Description
The main goal of this project is to develop a model predictive controller (NMPC) to steer a car around a track in a simulator. The simulator provides a set of values containing the position of the car, speed and heading direction. Additionally it provides the coordinates of waypoints along a reference trajectory that the car is to follow. All coordinates are provided in a global coordinate system.
The Vehicle Model
The kinematic model includes the vehicle's x and y coordinates, orientation angle (psi), and velocity, as well as the cross-track error and psi error (epsi). Actuator outputs are acceleration and delta (steering angle). The model combines the state and actuations from the previous timestep to calculate the state for the current timestep based on the equations below:
// x_[t+1] = x[t] + v[t] * cos(psi[t]) * dt
// y_[t+1] = y[t] + v[t] * sin(psi[t]) * dt
// psi_[t+1] = psi[t] + v[t] / Lf * delta[t] * dt
// v_[t+1] = v[t] + a[t] * dt
// cte[t+1] = f(x[t]) - y[t] + v[t] * sin(epsi[t]) * dt
// epsi[t+1] = psi[t] - psides[t] + v[t] * delta[t] / Lf * dt
State:
- px - The current location in the x-axis of an arbitrary global map coordinate system
- py - The current location in the y-axis of an arbitrary global map coordinate system
- psi - The current orientation / heading of the vehicle
- v - The current velocity/speed of the vehicle
Errors:
- cte - This is the cross track error which is the difference between our desired position and actual position.
- epsi - This is the orientation error which is the difference between our desired heading and actual heading.
Actuations:
- delta - This is the steering value which represents the angle of which we turn our vehicle (values between -1 and 1).
- a - This is the throttle or brake value which represents the acceleration or deceleration of our vehicle (values between -1 and 1).
Cost Function and Penalty Weights
The cost of a trajectory of length N is computed as follows
cost = A * cte^2 + B * epsi^2 + C * (v - vmax)^2 +
D * delta^2 + E * a^2 + F * (delta * v)^2 + G * (a` - a)^2 + H * (delta` - delta)^2
Additionally added penalty for steering and speed. This component has added stability to the car on sharp turns.
Ultimately here are the weights I ended up with:
A = 2000
B = 2000
C = 1
D = 1000
E = 5
F = 300
G = 1
H = 1
Latency
An additional complication of this project consists in taking delayed actuations into account. This latency is actually introduced before the actuations are sent back to the simulator. (main.cpp 134-136) This is equivalent to looking ahead while driving, realizing you can't do that much about what's immediately in front of you at highway speeds. One of the way to solve the problem is to incorporate the latency in the basic model by predicting the future car state after 100 ms time. The current state of the car is now the state after 100 ms and it is the state that the optimization will be conducted for.
const double latency = 0.1; // 100 ms
const double Lf = 2.67;
const double cur_v = v + a * latency;
const double cur_cte = cte + v * sin(epsi) * latency;
const double cur_epsi = epsi + v * (-delta) / Lf * latency;
The prediction horizon
The time T=N*dt defines the prediction horizon. Short prediction horizons lead to more responsive controlers, but are less accurate and can suffer from instabilities when chosen too short. Long prediction horizons generally lead to smoother controls but it is require more CPU resources. So I found that optimal for me is N = 10(±2), dt = 0.1
Polynomial Fitting and Preprocessing
The waypoints are preprocessed by transforming them to the vehicle's perspective . This simplifies the process to fit a polynomial to the waypoints because the vehicle's x and y coordinates are now at the origin (0, 0) and the orientation angle is also zero.
for (int i = 0; i < ptsx.size(); i++) {
const double dx = ptsx[i] - px;
const double dy = ptsy[i] - py;
ptsx[i] = (dx * cos(-psi) - dy * sin(-psi));
ptsy[i] = (dx * sin(-psi) + dy * cos(-psi));
}
Also was used the 3rd order polynomial as an estimate of the current road curve ahead, because it is good fit of most roads.
Simulation
The YouTube video seen here shows our car driving around the track with a speed limited to 90mph. The yellow lines indicate the "waypoints" from the simulator showing a preferred path forward. The green lines and dots show an optimal path predicted by our model controller.
Dependencies
- 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
- uWebSockets
- 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
- Fortran Compiler
- Mac:
brew install gcc
(might not be required) - Linux:
sudo apt-get install gfortran
. Additionall you have also have to install gcc and g++,sudo apt-get install gcc g++
. Look in this Dockerfile for more info.
- Mac:
- Ipopt
- If challenges to installation are encountered (install script fails). Please review this thread for tips on installing Ipopt.
- Mac:
brew install ipopt
- Some Mac users have experienced the following error:
This error has been resolved by updrading ipopt withListening to port 4567 Connected!!! mpc(4561,0x7ffff1eed3c0) malloc: *** error for object 0x7f911e007600: incorrect checksum for freed object - object was probably modified after being freed. *** set a breakpoint in malloc_error_break to debug
brew upgrade ipopt --with-openblas
per this forum post. - Linux
- You will need a version of Ipopt 3.12.1 or higher. The version available through
apt-get
is 3.11.x. If you can get that version to work great but if not there's a scriptinstall_ipopt.sh
that will install Ipopt. You just need to download the source from the Ipopt releases page. - Then call
install_ipopt.sh
with the source directory as the first argument, ex:sudo bash install_ipopt.sh Ipopt-3.12.1
.
- You will need a version of Ipopt 3.12.1 or higher. The version available through
- Windows: TODO. If you can use the Linux subsystem and follow the Linux instructions.
- CppAD
- Mac:
brew install cppad
- Linux
sudo apt-get install cppad
or equivalent. - Windows: TODO. If you can use the Linux subsystem and follow the Linux instructions.
- Mac:
- 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.
Basic Build Instructions
- Clone this repo.
- Make a build directory:
mkdir build && cd build
- Compile:
cmake .. && make
- Run it:
./mpc
.
Tips
- It's recommended to test the MPC on basic examples to see if your implementation behaves as desired. One possible example is the vehicle starting offset of a straight line (reference). If the MPC implementation is correct, after some number of timesteps (not too many) it should find and track the reference line.
- The
lake_track_waypoints.csv
file has the waypoints of the lake track. You could use this to fit polynomials and points and see of how well your model tracks curve. NOTE: This file might be not completely in sync with the simulator so your solution should NOT depend on it. - For visualization this C++ matplotlib wrapper could be helpful.
Editor Settings
We've purposefully kept editor configuration files out of this repo in order to keep it as simple and environment agnostic as possible. However, we recommend using the following settings:
- indent using spaces
- set tab width to 2 spaces (keeps the matrices in source code aligned)
Code Style
Please (do your best to) stick to Google's C++ style guide.
Project Instructions and Rubric
Note: regardless of the changes you make, your project must be buildable using cmake and make!
More information is only accessible by people who are already enrolled in Term 2 of CarND. If you are enrolled, see the project page for instructions and the project rubric.
Hints!
- You don't have to follow this directory structure, but if you do, your work will span all of the .cpp files here. Keep an eye out for TODOs.
Call for IDE Profiles Pull Requests
Help your fellow students!
We decided to create Makefiles with cmake to keep this project as platform agnostic as possible. Similarly, we omitted IDE profiles in order to we ensure that students don't feel pressured to use one IDE or another.
However! I'd love to help people get up and running with their IDEs of choice. If you've created a profile for an IDE that you think other students would appreciate, we'd love to have you add the requisite profile files and instructions to ide_profiles/. For example if you wanted to add a VS Code profile, you'd add:
- /ide_profiles/vscode/.vscode
- /ide_profiles/vscode/README.md
The README should explain what the profile does, how to take advantage of it, and how to install it.
Frankly, I've never been involved in a project with multiple IDE profiles before. I believe the best way to handle this would be to keep them out of the repo root to avoid clutter. My expectation is that most profiles will include instructions to copy files to a new location to get picked up by the IDE, but that's just a guess.
One last note here: regardless of the IDE used, every submitted project must still be compilable with cmake and make./