Skip to content

tw00/CarND-MPC-Project

 
 

Repository files navigation

CarND-Controls-MPC

Self-Driving Car Engineer Nanodegree Program


Model

The kinematic model used here is

alt text

where

  • x, y are car coordinates
  • psi is the car rotation angle
  • v is the velocity
  • delta is the steering wheel position
  • a is the acceleration (> 0) or brake (< 0)
  • Lf is distance between the front of the vehicle and its center of gravity

Model predictive control (MPC) optimizes the current and future actuator values (delta, a) to bring the state (x, y, psi, v) in a desired state, which is described by a loss function.

The following loss function is used here:

27     // minimize error towards reference state
28     for (int t = 0; t < N; t++) {
29       // put higher emphasis on the control task (minimize cte and orientation error)
30       cost += 1000 * CppAD::pow( vars[cte_start + t], 2 );
31       cost += 1000 * CppAD::pow( vars[epsi_start + t], 2 );
32     }
33     // minimize ref speed error
34     for (int t = 1; t < N; t++) {
35       // a weight of 10 results in an appropriate trade of between speed and control stability
36       cost += 10 * CppAD::pow(vars[v_start + t] - ref_v, 2);
37     }
38     // minimize actuators
39     for (int t = 0; t < N - 1; t++) {
40       cost += 3 * CppAD::pow(vars[delta_start + t], 2);
41       cost += 3 * CppAD::pow(vars[a_start + t], 2);
42     }
43     // minimize actuator speed
44     for (int t = 0; t < N - 2; t++) {
45       // especially limit actuator speed of steering wheel to prevent fast steering
46       cost += 1000 * CppAD::pow(vars[delta_start + t + 1] - vars[delta_start + t], 2);
47       cost +=    1 * CppAD::pow(vars[a_start + t + 1] - vars[a_start + t], 2);
48     }

where

  • cte is the cross track error
  • epsi is the error of orientation error
  • (v - ref_v) is the difference between current velocity and a desired velocity
  • delta^2 and a^2 limits the use of actuators
  • (delta - delta_prev)^2 and (a - a_prev)^2 limits the actuator speed

The weights are determined experimentally. A higher emphasis is put on optimizing the car's state itself and limiting the steering speed, resulting in smooth steering. Also an appropriate trade off between speed an stability needs to be found. Setting the weights for (v-ref_v) to 10 gives good results.

Hyper parameters

The optimizer predict N time steps with a delta of dt seconds between each prediction. The higher N the more the optimizer looks into the future. The smaller dt the higher the time resolution of predictions. Therefor N should be as large as possible, while dt should be as small as possible. The downside is that calculating a lot of prediction steps is computational expensive and therefor a trade off between optimization time and accuracy needs to be found. For the simulator the following values give good results:

  • dt = 0.1 (a time step of 0.1 provides enough resolution)
  • N = 10 (planing one second ahead is sufficient for this control task)

Car Latency

The latency (which is set to 100ms in the simulator) is considered by predicting the future state of the car using a motion model:

const double latency = 0.10;
px  += v * cos(psi) * latency;
py  += v * sin(psi) * latency;
psi -= ( v / Lf ) * delta * latency;
v   += a * latency;

Dependencies

  • cmake >= 3.5
  • All OSes: click here for installation instructions
  • make >= 4.1
  • gcc/g++ >= 5.4
  • uWebSockets
    • Run either install-mac.sh or install-ubuntu.sh.
    • If you install from source, checkout to commit e94b6e1, i.e.
      git clone https://github.com/uWebSockets/uWebSockets 
      cd uWebSockets
      git checkout e94b6e1
      
      Some function signatures have changed in v0.14.x. See this PR for more details.
  • 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.
  • Ipopt
    • Mac: brew install ipopt
    • 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 script install_ipopt.sh that will install Ipopt. You just need to download the source from the Ipopt releases page or the Github releases page.
      • Then call install_ipopt.sh with the source directory as the first argument, ex: bash install_ipopt.sh Ipopt-3.12.1.
    • 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.
  • 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

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

Tips

  1. 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.
  2. 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.
  3. 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./

About

Model Predictive Control (MPC) for autonomous cars

Resources

Stars

Watchers

Forks

Packages

No packages published

Languages

  • C++ 83.2%
  • Fortran 11.5%
  • C 2.0%
  • CMake 1.8%
  • Cuda 1.1%
  • Shell 0.2%
  • Other 0.2%