/CarND-MPC-Project

CarND Term 2 Model Predictive Control (MPC) Project

Primary LanguageC++MIT LicenseMIT

CarND-Controls-MPC

Self-Driving Car Engineer Nanodegree Program


Rubric Points

The Model

The code for the kinematic model is shown below:

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 - ((y0 - f0) + (v0 * CppAD::sin(epsi0) * dt));
fg[1 + epsi_start + t] =  epsi1 - ((psi0 - psides0) + v0 * delta0 / Lf * dt);
State Variables:
  • x: the x position of the car.
  • y: the y position of the car.
  • psi: the heading direction of the car.
  • v: the velocity of the car.
  • cte: the cross-track error.
  • epsi: the orientation error.
Control Variables:
  • delta: the steering angle.
  • a: the change of the speed.

Here, Lf is the distance between the center of mass of the vehicle and the front wheels and affects the maneuverability.

Timestep Length and Elapsed Duration (N & dt)

  • N = 10
  • dt = 0.1

Since the latency is given as 100ms (0.1s), I set dt = 0.1 in order to simplify the MPC implementation. For the timestep length N, it is always a, initially I tried 20 and 30, and the car was easy to oscillate. After that, I decided to use a smaller value and the car is able to handle the track without any issues.

Polynomial Fitting and MPC Preprocessing

To simplify the updating process, the waypoints are converted to the vehicle space, and a 3rd degree polynomials is used to fit waypoints:

for (int i = 0; i < ptsx.size(); i++) {
  waypoints_x.push_back((ptsx[i] - px) * cos(-psi) - (ptsy[i] - py) * sin(-psi));
  waypoints_y.push_back((ptsx[i] - px) * sin(-psi) + (ptsy[i] - py) * cos(-psi));
}

Eigen::Map<Eigen::VectorXd> ptsx_fit(&waypoints_x[0], waypoints_x.size());
Eigen::Map<Eigen::VectorXd> ptsy_fit(&waypoints_y[0], waypoints_y.size());

auto coeffs = polyfit(ptsx_fit, ptsy_fit, 3);
double cte = polyeval(coeffs, 0);
double epsi = -atan(coeffs[1]);

Model Predictive Control with Latency

Since I already set the timestep duration to be equal to the latency delay time, it is easy to handle the latency in MPC. As shown below, after the initial time, the actuators will always use the value from one more timestep ahead, which is exactly the latency delay time.

AD<double> delta0 = vars[delta_start + t - 1];
AD<double> a0 = vars[a_start + t - 1];
// latency
if (t > 1) {
  a0 = vars[a_start + t - 2];
  delta0 = vars[delta_start + t - 2];
}

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.

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.)
  4. Tips for setting up your environment are available here
  5. VM Latency: Some students have reported differences in behavior using VM's ostensibly a result of latency. Please let us know if issues arise as a result of a VM environment.

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

How to write a README

A well written README file can enhance your project and portfolio. Develop your abilities to create professional README files by completing this free course.