-
Notifications
You must be signed in to change notification settings - Fork 5
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Raceday 2017 - Fully Autonomous #458
Changes from all commits
99bd9f7
72c0a10
bb4aaf1
88a8c31
5ed83f1
d7de18c
9173567
8e48942
7bb13cd
a8bfbfd
3e7befc
1e32004
adc9406
bd74836
92955b8
c60f81f
4293f04
5742d56
3207333
18d6e0e
0d41949
68d4c62
3fa6827
60e7019
149ad4d
165a85a
87653d4
db8222a
7b9ce60
76ff3dd
f4a4c63
6c5a6b0
17b176e
0dce024
18b1602
57dfbf9
c9d6b0e
1acf75c
319317b
f4073f5
a389370
d85fa60
a002bc7
da9dc2d
91798c8
345d0ca
5083e8b
bf5e8b3
1a01e8e
4d047ae
64c0871
adbbcaf
2b644b1
c19df1a
3ff0acf
7c62772
caa2741
66bc66c
ed661a1
11da978
5a05eca
9c39475
9fcdec0
12e9f42
a30da60
aaa5f2f
1454400
a83d9c2
331f2ce
fc4fbff
300ab6e
16c843b
c4e007a
7ee21fd
0f9725e
29a9175
6360fa9
0a2a8c9
d688757
316df16
baf5d6c
619af97
c371f0e
f417a5b
f7f0b66
87b28ac
74ea873
7e7d686
63b50da
66c558d
f1466ae
984956d
4a7dafc
1200264
53febf2
a345948
a9ffef8
82bd186
df87f20
e8486ee
396a449
85a5128
34ddd6b
275d5f0
63b7c9b
48086f4
bbccdb2
fac6ceb
71e2b7a
e792a5a
aaf2ccc
c70f54b
fd867f8
41a94b7
3ef5bbc
7c9d37d
79ad673
4efb350
957d26e
ebfaf92
d5c2331
a2f77d5
7a68aa5
0f3dd51
f61f479
b7c1453
7db4bf1
cca6f42
06d5777
cf5accb
3162d7e
c76a1cc
3281dde
61ff1b9
d5cbc4f
70e66c6
66db548
085d06a
a4d8dc9
3704bea
bd0bc49
a411bd4
1038e8e
aa9c929
3670b88
a305d6d
8e0708e
500b0cc
5d71d04
c1e15ba
2482b7f
60ec6e6
d484efb
c84c36b
d9b6f1d
0783c18
d82c628
5dd245e
78f4631
91fc0aa
d0ec4f4
f5e568c
7113f08
5938c1a
0658e07
08406c9
4fe136c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,6 @@ | ||
*.mat | ||
*.jpg | ||
*.png | ||
.DS_Store | ||
*.pyc | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,125 @@ | ||
function [trajectory] = controller() | ||
|
||
addpath('../localizer/latlonutm/Codes/matlab'); | ||
global wheel_base | ||
global velocity | ||
global steering_vel | ||
global dt | ||
|
||
save_data = true; | ||
wheel_base = 1.13; | ||
utm_zone = 17; | ||
first_heading = deg2rad(250); | ||
lat_long = [40.441670, -79.9416362]; | ||
dt = 0.001; % 1000Hz | ||
m = 50; % 20Hz | ||
velocity = 8; % m/s, 17.9mph, forward velocity | ||
steering_vel = deg2rad(40); % 40deg/s, reaction speed to control cmds | ||
|
||
[x, y, ~] = ll2utm(lat_long(1), lat_long(2)); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. please document this a bit more maybe to clarify what this is doing There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
|
||
|
||
X = [x; % X, m, UTM coors | ||
y; % Y, m, UTM coors | ||
velocity; % d_Yb, body velocity | ||
first_heading; % heading, rad, world frame | ||
0]; % d_heading, rad/s | ||
|
||
load('./waypoints.mat'); | ||
desired_traj = processWaypoints(logs); | ||
% time = linspace(0, 240, size(trajectory,2)); | ||
time = 0:dt:240; | ||
u = 0; % commanded steering angle | ||
steering = u; % steering angle | ||
trajectory = [X; lat_long(1); lat_long(2); steering]; | ||
|
||
for i = 1:size(time, 2) | ||
t = time(i); | ||
A = model(X, steering); | ||
X = A*X; | ||
steering = updateSteering(steering, u); | ||
|
||
X(4) = clampAngle(X(4)); | ||
X(5) = clampAngle(X(5)); | ||
|
||
if(mod(i, m) == 0) | ||
u = control(desired_traj, X); | ||
end | ||
|
||
% trajectory = [trajectory, X]; | ||
snapshot = summarize(X, utm_zone, steering); | ||
trajectory = [trajectory, snapshot]; | ||
end | ||
|
||
if save_data | ||
save('controller_v2.mat', 'trajectory'); | ||
end | ||
end | ||
|
||
function [desired] = processWaypoints(lat_long) | ||
[x, y, zone] = ll2utm(lat_long); | ||
desired = [x y]; | ||
end | ||
|
||
function snapshot = summarize(x, utm_zone, steeringAngle) | ||
[lat, lon] = utm2ll(x(1), x(2), utm_zone); | ||
snapshot = [x; x(1); x(2); steeringAngle]; | ||
end | ||
|
||
function a = clampAngle(a) | ||
while (a < -pi) | ||
a = a + 2*pi; | ||
end | ||
while (a > pi) | ||
a = a - 2*pi; | ||
end | ||
end | ||
|
||
function b = updateSteering(b, u) | ||
global steering_vel | ||
global dt | ||
|
||
if(b < u) | ||
b = b + steering_vel*dt; | ||
end | ||
if(b > u) | ||
b = b - steering_vel*dt; | ||
end | ||
end | ||
|
||
function a = clampSteeringAngle(a) | ||
if(a < -deg2rad(10)) | ||
a = -deg2rad(10); | ||
end | ||
if(a > deg2rad(10)) | ||
a = deg2rad(10); | ||
end | ||
end | ||
|
||
function [A] = model(x, steering) | ||
global wheel_base | ||
global dt | ||
|
||
A = [1, 0, dt*cos(x(4)), 0, 0; | ||
0, 1, dt*sin(x(4)), 0, 0; | ||
0, 0, 1, 0, 0; | ||
0, 0, 0, 1, dt; | ||
0, 0, tan(steering)/wheel_base, 0, 0]; | ||
end | ||
|
||
function [u] = control(desired_traj, X) | ||
pos = X(1:2); | ||
b = repmat(pos, size(desired_traj, 1), 1); | ||
delta = 15*15; | ||
possible = find(sum((desired_traj-b).^2, 2) < delta); | ||
if isempty(possible) | ||
u = 0; | ||
else | ||
target = desired_traj(possible(end), :); | ||
deltaPath = target - pos; | ||
u = atan2(deltaPath(2), deltaPath(1))-X(4); | ||
end | ||
u = clampSteeringAngle(clampAngle(u)); | ||
end | ||
|
||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
% graph results | ||
|
||
clear; | ||
close all; | ||
|
||
addpath('../localizer/latlonutm/Codes/matlab'); | ||
addpath('../localizer/altmany-export_fig'); | ||
|
||
file = 'controller_v2.mat'; | ||
load(file, 'trajectory'); | ||
save_plot = false; | ||
show_maps = true; | ||
|
||
load('./waypoints_course_v2.mat'); | ||
[x, y, zone] = ll2utm(logs); | ||
desired = [x y]; | ||
desired = desired(112:(end-50), :); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Magic number |
||
|
||
k = 1000; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Magic number |
||
if show_maps | ||
wmline(trajectory(6,1:k:end), trajectory(7,1:k:end), 'Color', 'r') | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Magic number! |
||
end | ||
|
||
heading = trajectory(4,1:k:end); | ||
figure(); | ||
hold on; | ||
plot(trajectory(1,1:k:end), trajectory(2,1:k:end)) | ||
quiver(trajectory(1,1:k:end), trajectory(2,1:k:end), cos(heading), sin(heading)) | ||
plot(desired(:,1), desired(:,2), 'g') | ||
hold off; | ||
title(['Map ', file]); | ||
|
||
headingd = rad2deg(heading); | ||
figure(); | ||
hold on; | ||
plot(1:length(headingd), headingd) | ||
title(['Heading ', file]); | ||
|
||
figure(); | ||
p = k/20; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Magic number |
||
plot(1:p:size(trajectory,2), trajectory(8,1:p:end)) | ||
title('Control input'); | ||
|
||
% plot on google maps | ||
if show_maps | ||
xy = [trajectory(6,1:k:end); trajectory(7,1:k:end)]; | ||
fprintf(1, '%5.20f, %5.20f\n', xy); | ||
end |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,137 @@ | ||
function [trajectory] = controller_pure() | ||
% https://www.ri.cmu.edu/pub_files/2009/2/Automatic_Steering_Methods_for_Autonomous_Automobile_Path_Tracking.pdf | ||
% section 2.2 | ||
|
||
addpath('../localizer/latlonutm/Codes/matlab'); | ||
global wheel_base | ||
global velocity | ||
global steering_vel | ||
global dt | ||
|
||
save_data = true; | ||
wheel_base = 1.13; | ||
utm_zone = 17; | ||
first_heading = deg2rad(250); | ||
lat_long = [40.442867, -79.9427395]; % [40.441670, -79.9416362]; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Magic numbers |
||
dt = 0.001; % 1000Hz | ||
m = 50; % 20Hz | ||
velocity = 8; % m/s, 17.9mph, forward velocity | ||
steering_vel = deg2rad(40); % 40deg/s, reaction speed to control cmds | ||
% full range in 0.5s | ||
|
||
[x, y, ~] = ll2utm(lat_long(1), lat_long(2)); | ||
|
||
X = [x; % X, m, UTM coors | ||
y; % Y, m, UTM coors | ||
velocity; % d_Yb, body velocity | ||
first_heading; % heading, rad, world frame | ||
0]; % d_heading, rad/s | ||
|
||
load('./waypoints_tri.mat'); | ||
desired_traj = processWaypoints(logs); | ||
% time = linspace(0, 240, size(trajectory,2)); | ||
time = 0:dt:60; % 240; | ||
u = 0; % commanded steering angle | ||
steering = u; % steering angle | ||
trajectory = [X; lat_long(1); lat_long(2); steering]; | ||
|
||
for i = 1:size(time, 2) | ||
t = time(i); | ||
A = model(X, steering); | ||
X = A*X; | ||
steering = updateSteering(steering, u); | ||
|
||
X(4) = clampAngle(X(4)); | ||
X(5) = clampAngle(X(5)); | ||
|
||
if(mod(i, m) == 0) | ||
u = control(desired_traj, X); | ||
end | ||
|
||
% trajectory = [trajectory, X]; | ||
snapshot = summarize(X, utm_zone, steering); | ||
trajectory = [trajectory, snapshot]; | ||
end | ||
|
||
if save_data | ||
save('controller_tri_v1.mat', 'trajectory'); | ||
end | ||
end | ||
|
||
function [desired] = processWaypoints(lat_long) | ||
[x, y, zone] = ll2utm(lat_long); | ||
desired = [x y]; | ||
end | ||
|
||
function snapshot = summarize(x, utm_zone, steeringAngle) | ||
[lat, lon] = utm2ll(x(1), x(2), utm_zone); | ||
snapshot = [x; x(1); x(2); steeringAngle]; | ||
end | ||
|
||
function a = clampAngle(a) | ||
while (a < -pi) | ||
a = a + 2*pi; | ||
end | ||
while (a > pi) | ||
a = a - 2*pi; | ||
end | ||
end | ||
|
||
function b = updateSteering(b, u) | ||
global steering_vel | ||
global dt | ||
|
||
if(b < u) | ||
b = b + steering_vel*dt; | ||
end | ||
if(b > u) | ||
b = b - steering_vel*dt; | ||
end | ||
end | ||
|
||
function a = clampSteeringAngle(a) | ||
if(a < -deg2rad(10)) | ||
a = -deg2rad(10); | ||
end | ||
if(a > deg2rad(10)) | ||
a = deg2rad(10); | ||
end | ||
end | ||
|
||
function [A] = model(x, steering) | ||
global wheel_base | ||
global dt | ||
|
||
A = [1, 0, dt*cos(x(4)), 0, 0; | ||
0, 1, dt*sin(x(4)), 0, 0; | ||
0, 0, 1, 0, 0; | ||
0, 0, 0, 1, dt; | ||
0, 0, tan(steering)/wheel_base, 0, 0]; | ||
end | ||
|
||
function [u] = control(desired_traj, X) | ||
global wheel_base | ||
|
||
pos = X(1:2)'; | ||
pos_b = repmat(pos, size(desired_traj, 1), 1); | ||
delta = 15; | ||
cutoff = 100; | ||
delta = delta * delta; | ||
|
||
distances = sum((desired_traj - pos_b).^2, 2); | ||
[~, closest_idx] = min(distances); | ||
last_idx = min([length(distances), closest_idx + cutoff]); | ||
possible = find(distances(1:last_idx) < delta); | ||
if isempty(possible) | ||
u = 0; | ||
else | ||
target = desired_traj(possible(end), :); | ||
deltaPath = target - pos; | ||
|
||
k = 0.8; | ||
a = atan2(deltaPath(2), deltaPath(1))-X(4); | ||
u = atan2(2*wheel_base*sin(a), k*X(3)); | ||
end | ||
u = clampSteeringAngle(clampAngle(u)); | ||
end | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Bunch of magic numbers used