Skip to content
This repository has been archived by the owner on Sep 15, 2022. It is now read-only.

Commit

Permalink
Merge pull request #5 from udacity/ck/AddFilesForRealLifeTesting
Browse files Browse the repository at this point in the history
add launch files for site testing, adjust acceleration value
  • Loading branch information
ckirksey3 authored Aug 25, 2017
2 parents b74f35e + 77ad230 commit a609fab
Show file tree
Hide file tree
Showing 5 changed files with 87 additions and 2 deletions.
61 changes: 61 additions & 0 deletions data/churchlot_with_cars.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
10.4062,15.581,0.775,-2.7419,12
9.3323,15.1076,0.7265,-2.7761,12
8.2133,14.6523,0.6463,-2.7875,12
7.1124,14.2238,0.5837,-2.7816,12
6.1445,13.8196,0.5186,-2.7624,12
5.1563,13.3232,0.4582,-2.7233,12
4.0306,12.8497,0.4001,-2.6551,12
2.9963,12.3614,0.3606,-2.5595,12
2.1433,11.6514,0.324,-2.4223,12
1.3549,10.8159,0.3129,-2.2498,12
0.6673,9.8075,0.2927,-2.0473,12
0.0982,8.8679,0.2952,-1.829,12
-0.1674,7.7939,0.2971,-1.5273,12
-0.016,6.7165,0.3308,-1.2993,12
0.4703,5.6266,0.3591,-1.0645,12
1.0478,4.6374,0.44,-0.8443,12
1.7823,3.662,0.5316,-0.643,12
2.8056,2.9294,0.618,-0.4675,12
3.752,2.5905,0.639,-0.3436,12
4.8491,2.3299,0.6923,-0.2324,12
5.9542,2.1258,0.7686,-0.1403,12
7.1193,1.9555,0.845,-0.072,12
8.329,1.8898,0.8918,-0.0299,12
9.5629,1.8863,0.9811,-0.0096,12
10.8273,1.9032,1.0635,0.0055,12
12.0401,1.9231,1.134,0.0154,12
13.2311,1.9756,1.2247,0.0259,12
14.454,2.0982,1.2894,0.0491,12
15.667,2.1955,1.358,0.0874,12
16.8044,2.3517,1.4531,0.142,12
17.9644,2.5628,1.5041,0.2087,12
19.1917,2.8108,1.5556,0.2976,12
20.2247,3.1073,1.6655,0.4049,12
21.1457,3.5801,1.7298,0.5225,12
21.9855,4.1788,1.7631,0.6443,12
22.7811,4.8316,1.8034,0.7734,12
23.5077,5.622,1.8373,0.9148,12
24.1083,6.4314,1.8431,1.0537,12
24.7628,7.5022,1.8801,1.2454,12
25.0165,8.5624,1.9044,1.439,12
24.9825,9.7477,1.8986,1.6241,12
24.8426,10.9168,1.8811,1.801,12
24.5885,12.16,1.8511,1.9861,12
24.1027,13.3017,1.8157,2.1751,12
23.3313,14.2742,1.7346,2.3716,12
22.4417,14.9339,1.6529,2.514,12
21.549,15.5242,1.5707,2.6533,12
20.4978,16.0282,1.4939,2.788,12
19.4593,16.3515,1.4019,2.9136,12
18.3935,16.6445,1.3187,3.0424,12
17.3152,16.7253,1.2257,3.1397,12
16.2105,16.6429,1.1768,-3.0689,12
15.1095,16.4975,1.0757,-3.0101,12
14.0054,16.3033,1.0277,-2.9785,12
12.9916,16.1129,0.9634,-2.9596,12
11.9502,15.8813,0.8892,-2.9351,12
10.8016,15.601,0.8146,-2.9138,12
9.7822,15.3713,0.7315,-2.8976,12
8.8213,15.0926,0.698,-2.8836,12
7.6275,14.7692,0.6189,-2.8695,12
6.6734,14.4438,0.5474,-2.8635,12
17 changes: 17 additions & 0 deletions ros/launch/site.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<launch>
<!--DBW Node -->
<include file="$(find twist_controller)/launch/dbw.launch"/>

<!--Waypoint Loader -->
<include file="$(find waypoint_loader)/launch/waypoint_loader_site.launch"/>

<!--Waypoint Follower Node -->
<include file="$(find waypoint_follower)/launch/pure_pursuit.launch"/>

<!--Waypoint Updater Node -->
<include file="$(find waypoint_updater)/launch/waypoint_updater.launch"/>

<!--Traffic Light Detector Node -->
<include file="$(find tl_detector)/launch/tl_detector.launch"/>
</launch>
2 changes: 1 addition & 1 deletion ros/src/twist_controller/launch/dbw.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<param name="vehicle_mass" value="1736.35" />
<param name="fuel_capacity" value="13.5" />
<param name="brake_deadband" value=".1" />
<param name="decel_limit" value="-5." />
<param name="decel_limit" value="-1." />
<param name="accel_limit" value="1." />
<param name="wheel_radius" value="0.2413" />
<param name="wheel_base" value="2.8498" />
Expand Down
2 changes: 1 addition & 1 deletion ros/src/waypoint_follower/src/pure_pursuit_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -317,7 +317,7 @@ geometry_msgs::TwistStamped PurePursuit::outputZero() const
}
geometry_msgs::TwistStamped PurePursuit::outputTwist(geometry_msgs::Twist t) const
{
double g_lateral_accel_limit = 0.8;
double g_lateral_accel_limit = 5.0;
double ERROR = 1e-8;

geometry_msgs::TwistStamped twist;
Expand Down
7 changes: 7 additions & 0 deletions ros/src/waypoint_loader/launch/waypoint_loader_site.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<?xml version="1.0"?>
<launch>
<node pkg="waypoint_loader" type="waypoint_loader.py" name="waypoint_loader">
<param name="path" value="$(find styx)../../../data/churchlot_with_cars.csv" />
<param name="velocity" value="10" />
</node>
</launch>

0 comments on commit a609fab

Please sign in to comment.