/CarND-MPC-P10

Self Driving Car - Model Predictive Control (MPC) Project - Udacity

Primary LanguageC++

CarND-Controls-MPC

Self-Driving Car Engineer Nanodegree Program

Model Predictive Control for Self-Driving Cars

Overview

The purpose of this project is to develop a nonlinear model predictive controller (NMPC) to steer a car around a track in a simulator.

The simulator feeds the controller its current state (speed, steering, throttle) and waypoints, and the controller creates a reference trajectory, along the center of the lane, and attempts to follow the reference trajectory as closely as possible, without steering off the track.

The Vehicle Model

The vehicle model used in this project is a kinematic bicycle model. It neglects all dynamical effects such as inertia, friction and torque. The model takes changes of heading direction into account and is thus non-linear. The model used consists of the following equations

fg[1 + x_start + t]   = x1    - (x0 + v0 * CppAD::cos(psi0) * dt);
fg[1 + y_start + t]   = y1    - (y0 + v0 * CppAD::sin(psi0) * dt);
fg[1 + psi_start + t] = psi1  - (psi0 + v0 * delta0 / Lf * dt);
fg[1 + v_start + t]   = v1    - (v0 + a0 * dt);
fg[1 + cte_start + t] = cte1  - ((f0 - y0) + (v0 * CppAD::sin(epsi0) * dt));
fg[1 + epsi_start + t]= epsi1 - ((psi0 - psides0) + v0 * delta0 / Lf * dt);

Here, the Lf is the the vehicle's manoeuvrability, and is the distance between its center of gravity and front wheels, and is determined empirically.

The model works by tracking two errors: Cross Tracking Error (CTE) and Orientation Error (Epsi), and by attempting to reduce these two errors as it follows a reference trajectory.

x,y denote the position of the car, psi the heading direction, v its velocity.

The vehicle model can be found in the class FG_eval

state description
x position in x-direction
y position in y-direction
psi orientation
v velocity
cte cross track error
epsi orientation error

The following actuators are used to control the vehicle: delta, a:

actuator description limits
delta steering angle [-25°, 25°]
a throttle/brake [-1, 1]

Time Step and Duration

The MPC model works by creating a predicted reference trajectory for T seconds ahead on the horizon of its current position. Since T = N * dt, where N is number of timesteps and dt is the timeperiod delta (in seconds), I started off with small values of N and dt.

Larger values of T means longer horizons and smoother changes over time, but also larger deviations in tracking as horizons can change dramatically; smaller T means shorted horizons, more responsiveness and more accurate, but means more discrete changes.

Using a reference target speed of 50 mph, I started with dt = 0.05 and N = 10. Increasing the max velocity led to oscillations of vehicle. In the, with trial and error, I settled down to N = 12 and dt = 0.05, with velocity slowly increasing from ~30 mph to 85 mph (final).

Cost and Error Tracking

The model calculates error by assigning a Cost function and fitting a polynomial to the reference (projected) trajectory, iteratively for each waypoint. As the vehicle's current state matches the reference trajectory, the error from deviation (or cost) is minimized; as the vehicle does not match the trajectory, the error (or cost) increases. The optimization to reduce the cost function is performed by IpOpt library.

The cost function includes three components:

  • Cost based on Reference State. This cost penalizes the magnitude of CTE and Epsi; the larger the magnitudes, the higher the costs.

  • Cost based on Rate of Change of Actuations. This cost penalizes the rate of change of CTE and Epsi, so that vehicles do not abruptly jerk left/right.

  • Cost based on Sequential Actuations. This cost penalizes the gap between sequential actuations.

         // 1. Cost Function
         // State: [x,y,ψ,v,cte,eψ]
         // 1a - Cost based on Reference State; for Trajectory, set cost to 0
         for (int t = 0; t < N; t++) {
           fg[0] +=  1.0 * CppAD::pow(vars[cte_start + t] - REF_CTE, 2);   // Cross Track Error
           fg[0] +=  1.0 * CppAD::pow(vars[epsi_start + t] - REF_EPSI, 2); // Orientation error
           fg[0] +=  1.0 * CppAD::pow(vars[v_start + t] - REF_V, 2);       // Velocity error
         }
     
         // 1b - Minimise the use of Actuators
         // Add Scaling factor to smooth out
         for (int t = 0; t < N - 1; t++) {
           fg[0] +=  SCALE_DELTA * CppAD::pow(vars[delta_start + t], 2);
           fg[0] +=  SCALE_ACC   * CppAD::pow(vars[a_start + t], 2);
         }
     
         // 1c - Minimize the value gap between sequential actuations
         // Add Scaling factor to smooth out
         for (int t = 0; t < N - 2; t++) {
           fg[0] +=  SCALE_DELTA_D * CppAD::pow(vars[delta_start + t + 1] - vars[delta_start + t], 2);
           fg[0] +=  SCALE_ACC_D   * CppAD::pow(vars[a_start + t + 1]  - vars[a_start + t], 2);
         }
     
    

To account for sudden changes in CTE and EPsi, a scaling factor was added that keeps the various cost components together. This nicely enables us to tune the various cost components individually.

const double SCALE_DELTA  = 1.0;
const double SCALE_ACC    = 10.0;
const double SCALE_DELTA_D = 400.0;
const double SCALE_ACC_D  = 2.0;

Increasing the weight on different cost components ensures smoother vehicle handling (turns and acceleration). A major effort of tuning went into selecting various values by trial and error. The Cost function is implemented in FG_eval.

Polynomial Fitting

The simulator sends its coordinates to the MPC controller in the global Map coordinates. These waypoints are converted into Vehicle's coordinates using a transform. This is implemented in convertoToCarCoordinates in main.cpp. The transform essentially shifts the origin to the vehicle's current position, and then applies a 2D rotation to align x-axis to the heading of the vehicle.

New X = cos(psi) * (mapX - x) + sin(psi) * (mapY - y)
New Y = -sin(psi) * (mapX - x) + cos(psi) * (mapY - y)

This ensures that state of the vehicle is [0, 0, 0, v, cte, epsi] (the first three 0s are x,y,psi).

Latency

In real world, the actuations on steering and throttle take finite amount of time to take effect. In this case, a latency of 100 ms is given. When latency delays are not taken into account, the vehicle can sometimes be in an unpredictable state.

To counter the effect of latency, constraints were introduced for the duration of latency (100 ms, which is 2 dt timesteps). The actuations values of previous iteration were stored and applied for the duration of latency; this ensures that actuations are smooth, and optimal trajectory is calculated starting from time after the latency. This is implemented in MPC::Solve.

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./