-
Notifications
You must be signed in to change notification settings - Fork 2
/
Handlingtrack_DV.m
265 lines (210 loc) · 8.96 KB
/
Handlingtrack_DV.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
clear all
close all
clc
%% cost map
costmap = helperSLCreateCostmap_H();
h = figure;
plot(costmap)
%% Route planner
maxSteeringAngle = 120; % in degrees
vehicleDims = vehicleDimensions(4.5,1.7);
costmap.CollisionChecker.VehicleDimensions = vehicleDims;
load('plannerpoints_handling')
load('theta')
currentPose =[out(1,1) out(1,2) teta_req(1,1)];
for i = 1:1:length(out)
% if length(teta_req)>length(out)
StartPose = [out(i,1) out(i,2) teta_req(i,1)];
% else
% teta_req((length(out)),1)= teta_req(8,1);
% end
end
StartPose = [out(:,1) out(:,2) teta_req(:,1)];
EndPose =[]
for j = 2:1:length(StartPose)
EndPose = [EndPose;[StartPose(j,1) StartPose(j,2) teta_req(j,1)]];
end
for k= length(EndPose)+1
EndPose(k,1) = currentPose(1,1);
EndPose(k,2) = currentPose(1,2);
EndPose(k,3) = currentPose(1,3);
end
degree = [StartPose(:,3) EndPose(:,3)];
data = table(StartPose,EndPose,degree);
RoutePlan = data;
data = load('routePlanSL2_H.mat');
routePlan = data.routePlan %#ok<NOPTS>
currentPose = [routePlan.StartPose(1,1) routePlan.StartPose(1,2) routePlan.StartPose(1,3)];
hold on
helperPlotVehicle(currentPose, vehicleDims, 'DisplayName', 'Current Pose')
legend
for n = 1 : height(routePlan)
% Extract the goal waypoint
vehiclePose = routePlan{n, 'EndPose'};
% Plot the pose
legendEntry = sprintf('Goal %i', n);
helperPlotVehicle(vehiclePose, vehicleDims, 'DisplayName', legendEntry);
end
hold off
BehavioralPlanner = HelperBehavioralPlanner(routePlan, maxSteeringAngle);
motionPlanner = pathPlannerRRT(costmap, 'MinIterations', 1000, ...
'ConnectionDistance',20, 'MinTurningRadius', 5);
goalPose = routePlan{1, 'EndPose'};
refPath = plan(motionPlanner, currentPose, goalPose);
refPath.PathSegments
[transitionPoses, directions] = interpolate(refPath);
% Visualize the planned path
plot(motionPlanner)
hold off
% Specify number of poses to return using a separation of approximately 0.1 m
approxSeparation = 0.1; % meters
%refPath.Length1 = 1
refPath1.Length = 50;
%numSmoothPoses1 = round(refPath1.Length / approxSeparation);
numSmoothPoses = round(refPath1.Length / approxSeparation);
% Return discretized poses along the smooth path
%[refPoses1, directions1, cumLengths1, curvatures1] = smoothPathSpline(transitionPoses1, directions1, numSmoothPoses1);
[refPoses, directions, cumLengths, curvatures] = smoothPathSpline(transitionPoses, directions, numSmoothPoses);
% Plot the smoothed path
hold on
% hSmoothPath1 = plot(refPoses1(:, 1), refPoses1(:, 2), 'g', 'LineWidth', 2, ...
% 'DisplayName', 'Smoothed Path1');
hSmoothPath = plot(refPoses(:, 1), refPoses(:, 2), '--k', 'LineWidth', 1, ...
'DisplayName', 'Smoothed Path2');
%% Velocity profiler
maxSpeed = 10; % in meters/second
startSpeed = 1; % in meters/second
endSpeed = 0; % in meters/second
refVelocities = helperGenerateVelocityProfile(directions, cumLengths, curvatures, startSpeed, endSpeed, maxSpeed);
% figure (2)
% plot(refVelocities,'k', 'LineWidth', 2)
% hold on
% plot (maxSpeed,'g', 'LineWidth', 2)
% hold off
%plotVelocityProfile(cumLengths, refVelocities, maxSpeed)
%% Vehicle control and simulation
%closeFigures;
% Create the vehicle simulator
vehicleSim = HelperVehicleSimulator(costmap, vehicleDims);
% Set the vehicle pose and velocity
vehicleSim.setVehiclePose(currentPose);
currentVel = 0;
vehicleSim.setVehicleVelocity(currentVel);
% Configure the simulator to show the trajectory
vehicleSim.showTrajectory(true);
% Hide vehicle simulation figure
showFigure(vehicleSim);
% x0 = 59;
% y0 = 180;
% theta0= 90;
pathAnalyzer = HelperPathAnalyzer(refPoses, refVelocities, directions, ...
'Wheelbase', vehicleDims.Wheelbase)
sampleTime = 0.05;
lonController = HelperLongitudinalController('SampleTime', sampleTime);
controlRate = HelperFixedRate(1/sampleTime); % in Hertz
reachGoal = false;
Str=[];
%
while ~reachGoal
% Find the reference pose on the path and the corresponding velocity
[refPose, refVel, direction] = pathAnalyzer(currentPose, currentVel);
% Update driving direction for the simulator
updateDrivingDirection(vehicleSim, direction);
% Compute steering command
steeringAngle = lateralControllerStanley(refPose, currentPose, currentVel, ...
'Direction', direction, 'Wheelbase', vehicleDims.Wheelbase);
Str(end+1)= steeringAngle;
% Compute acceleration and deceleration commands
lonController.Direction = direction;
[accelCmd, decelCmd] = lonController(refVel, currentVel);
% Simulate the vehicle using the controller outputs
drive(vehicleSim, accelCmd, decelCmd, steeringAngle);
% Check if the vehicle reaches the goal
reachGoal = helperGoalChecker(goalPose, currentPose, currentVel, endSpeed, direction);
% Wait for fixed-rate execution
waitfor(controlRate);
% Get current pose and velocity of the vehicle
currentPose = getVehiclePose(vehicleSim);
currentVel = getVehicleVelocity(vehicleSim);
end
%
% Show vehicle simulation figure
showFigure(vehicleSim);
figure(4)
plot((0:length(Str)-1)*j,Str)
%hold on
%plot(curvatures)
%% Execute a Complete Plan
% Now combine all the previous steps in the planning process and run the
% simulation for the complete route plan. This process involves
% incorporating the behavioral planner.
% Set the vehicle pose back to the initial starting point
currentPose = [59,180, 90]; % [x, y, theta]
vehicleSim.setVehiclePose(currentPose);
% Reset velocity
currentVel = 0; % meters/second
vehicleSim.setVehicleVelocity(currentVel);
while ~reachedDestination(BehavioralPlanner)
% Request next maneuver from behavioral layer
[nextGoal, plannerConfig, speedConfig] = requestManeuver(BehavioralPlanner, ...
currentPose, currentVel);
% Configure the motion planner
configurePlanner(motionPlanner, plannerConfig);
% Plan a reference path using RRT* planner to the next goal pose
refPath = plan(motionPlanner, currentPose, nextGoal);
% Check if the path is valid. If the planner fails to compute a path,
% or the path is not collision-free because of updates to the map, the
% system needs to re-plan. This scenario uses a static map, so the path
% will always be collision-free.
isReplanNeeded = ~checkPathValidity(refPath, costmap);
if isReplanNeeded
warning('Unable to find a valid path. Attempting to re-plan.')
% Request behavioral planner to re-plan
replanNeeded(BehavioralPlanner);
continue;
end
% Retrieve transition poses and directions from the planned path
[transitionPoses, directions] = interpolate(refPath);
% Smooth the path
numSmoothPoses = round(refPath.Length / approxSeparation);
[refPoses, directions, cumLengths, curvatures] = smoothPathSpline(transitionPoses, directions, numSmoothPoses);
% Generate a velocity profile
refVelocities = helperGenerateVelocityProfile(directions, cumLengths, curvatures, startSpeed, endSpeed, maxSpeed);
% Configure path analyzer
pathAnalyzer.RefPoses = refPoses;
pathAnalyzer.Directions = directions;
pathAnalyzer.VelocityProfile = refVelocities;
% Reset longitudinal controller
reset(lonController);
reachGoal = false;
% Execute control loop
while ~reachGoal
% Find the reference pose on the path and the corresponding velocity
[refPose, refVel, direction] = pathAnalyzer(currentPose, currentVel);
% Update driving direction for the simulator
updateDrivingDirection(vehicleSim, direction);
% Compute steering command
steeringAngle = lateralControllerStanley(refPose, currentPose, currentVel, ...
'Direction', direction, 'Wheelbase', vehicleDims.Wheelbase);
% Compute acceleration and deceleration commands
lonController.Direction = direction;
[accelCmd, decelCmd] = lonController(refVel, currentVel);
% Simulate the vehicle using the controller outputs
drive(vehicleSim, accelCmd, decelCmd, steeringAngle);
% Check if the vehicle reaches the goal
reachGoal = helperGoalChecker(nextGoal, currentPose, currentVel, speedConfig.EndSpeed, direction);
% Wait for fixed-rate execution
waitfor(controlRate);
% Get current pose and velocity of the vehicle
currentPose = getVehiclePose(vehicleSim);
currentVel = getVehicleVelocity(vehicleSim);
end
end
% Show vehicle simulation figure
showFigure(vehicleSim);
%load('helperSLCreateUtilityBus.mat');
open_system('Handlingmodel');
set_param('Handlingmodel','SimulationCommand','Update');
open_system('Handlingmodel/Vehicle Controller')
open_system('Handlingmodel/Vehicle Model');
sim('Handlingmodel')