This is the Capstone project for the Udacity Self-Driving Car Nanodegree. We developed software to guide a real self-driving car around a test track. Using the Robot Operating System (ROS), we created nodes for traffic light detection and classification, trajectory planning, and control.
- Reloading PID parameters while the car is running for faster tuning
- Trajectory plans with multiple successive behaviors so that trajectory planner works well at low frequency
- RViz visualization of car, traffic lights, and trajectory plan
- Smoother acceleration with lower message frequency by adding linear interpolation to the "pure pursuit" code and replacing speed with acceleration in twist messages
- Automatic, real-time adjustments to throttle gain
- Color added to the traffic light message format for smoother stops
- UNet architecture for traffic light detection
- Automated testing via rostest
Note: Find the latest version of this project on Github.
- Eric Lavigne - team lead
- William Xu - visualization and controller
- Alena Kastsiukavets - traffic light detection
- Mihir Rajput - trajectory planner
- Sergey Vandyshev - traffic light classification
- diagram of nodes and messages
- UNet architecture
- NN is pretrained on medical images from Kaggle competition
- Trained on black-and-white images
- Custom loss function is used based on Dice coefficient
- Separate models for simulator (Dice coefficient is 0.81) and Carla (Dice coefficient is 0.66)
- See training code in detector and inference code in tl_detector.py.
Simulator Model | Carla Model |
---|---|
- Four output classes: GREEN, YELLOW, RED, NONE.
- Test accuracy was 100% for simulator images and 84.7% for Carla images.
- See model and training code for Carla and Simulator in iPython notebooks.
- See inference code in tl_classifier.py.
Decision Function | Ideal Scenario |
---|---|
- Acceleration and deceleration profiles are governed by the kinematic equations of motion.
- Safe distance allows deceleration at 10% of maximum deceleration while still stopping in time.
- If further than safe distance from the traffic light, the car ignores the traffic light's color and accelerates up to cruising speed.
- Within safe distance of a traffic light, car decelerates at whatever rate would result in stopping exactly on the stop line.
- When car within stopping distance (3 meters) of yellow or red light, it will decelerate at maximum deceleration.
- When car is less than hysteresis distance (1 meter) past the stop line at a yellow or red light, it will continue max deceleration.
- When car is more than hysteresis distance (1 meter) past the stop line, or if the traffic light turns green, car will accelerate up to cruising speed.
- See code in waypoint_updater.py.
- Substantial improvement over original "pure pursuit" version provided by Udacity
- Originally determined intended speed based only on first waypoint, which quickly became stale
- Originally reported intended speed to stability controller, which also quickly became stale
- Changed to consider current position and varying lookahead distance depending on speed
- Changed message format from speed to acceleration, which is much more stable
- See code in pure_pursuit_core.cpp#calcAcceleration.
- Tuned PID parameters with sliders while the simulator was running.
- Tuned for high speed in simulator.
- Needed for moderating the output of waypoint follower and preventing overshoot.
- See code in stability_controller.py.
- We know that the real car has a much more sensitive throttle and brake than the simulator, but don't have enough information to calculate this difference.
- The effect of throttle on acceleration is also very non-linear depending on car's speed.
- Use a series of linear models for 0-10mph, 10-20mph, 20-30mph, etc.
- For each of these small speed ranges, assume required throttle or brake is linear function of current speed and intended acceleration.
- Collect data from car behavior for on-the-fly calibration of throttle and brake models
- See code in gain_controller.py.
-
Be sure that your workstation is running Ubuntu 16.04 Xenial Xerus or Ubuntu 14.04 Trusty Tahir. Ubuntu downloads can be found here.
-
If using a Virtual Machine to install Ubuntu, use the following configuration as minimum:
- 2 CPU
- 2 GB system memory
- 25 GB of free hard drive space
The Udacity provided virtual machine has ROS and Dataspeed DBW already installed, so you can skip the next two steps if you are using this.
-
Follow these instructions to install ROS
- ROS Kinetic if you have Ubuntu 16.04.
- ROS Indigo if you have Ubuntu 14.04.
-
- Use this option to install the SDK on a workstation that already has ROS installed: One Line SDK Install (binary)
-
Download the Udacity Simulator.
- Clone the project repository
git clone https://github.com/udacity/CarND-Capstone.git
- Install python dependencies
cd CarND-Capstone
pip install -r requirements.txt
- Make and run styx
cd ros
./rebuild-all.sh
source devel/setup.sh
roslaunch launch/styx.launch
- Run the simulator
cd ros
./rebuild-all.sh
source devel/setup.sh
roslaunch launch/wolfpack.launch use_ground_truth:=true
# running rqt_gui in a different terminal
rqt --perspective-file "$(rospack find wolfpack_visualisation)/launch/rqt.perspective"
If the car does not move or behaves poorly, try applying the "eventlet monkey patch" with this modification to the roslaunch command. This helps on some computers and hurts on others, so try both ways if you're having problems.
EVENTLET_MONKEY_PATCH=true roslaunch launch/styx.launch
- Download training bag that was recorded on the Udacity self-driving car
- Unzip the file
unzip traffic_light_bag_files.zip
- Play the bag file
rosbag play -l traffic_light_bag_files/loop_with_traffic_light.bag
- Launch your project in site mode
cd CarND-Capstone/ros
roslaunch launch/site.launch
To run a single unit test with all the rosout logging in the console
# rostest from ros dir
rostest --text src/waypoint_updater/test/waypoint_updater.test
# nosetest from ros dir
nosetests -s src/twist_controller/test/test_stability_controller.py
To run all ROS unit tests
# from ros dir
catkin_make run_tests
To watch for file changes and run unit tests on any file modifications. If the below commands don't work on windows then change the watch-run.sh, uncomment the inotify command and comment out the existing inotify command
# from ros dir watch src dir and run single test
./watch-run.sh src "rostest --text src/waypoint_updater/test/waypoint_updater.test"
# from ros dir watch src dir and run nosetest
./watch-run.sh src "nosetests -s src/twist_controller/test/test_stability_controller.py"
# from ros dir watch src dir and run all unit tests
./watch-run.sh src "catkin_make run_tests"
read http://wiki.ros.org/rostest/Writing
-
Create a ROS test file e.g.
ros/src/waypoint_updater/test/test_waypoint_updater.py
-
Create a launch file with the node to test. Add a node pointing to the test file e.g.
ros/src/waypoint_updater/test/waypoint_updater.test
<launch>
<node pkg="mypkg" type="mynode" name="mynode" />
<test test-name="test_mynode" pkg="mypkg" type="test_mynode" />
</launch>
- add to CmakeLists.txt in the module
if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest(test/waypoint_updater.test)
endif()
- Add the below to the package.xml
<build_depend>rostest</build_depend>
- Create plain Python unit test file
- Add to CmakeLists.txt in the Testing section
## Add folders to be run by python nosetests
catkin_add_nosetests(test/test_stability_controller.py)