12
12
import math
13
13
import matplotlib .pyplot as plt
14
14
import sys
15
- sys .path .append ("../ReedsSheppPath/" )
15
+ import os
16
+
17
+ sys .path .append (os .path .dirname (os .path .abspath (__file__ ))
18
+ + "/../ReedsSheppPath" )
16
19
try :
17
20
from a_star_heuristic import dp_planning # , calc_obstacle_map
18
21
import reeds_shepp_path_planning as rs
19
22
from car import move , check_car_collision , MAX_STEER , WB , plot_car
20
- except :
23
+ except Exception :
21
24
raise
22
25
23
26
24
27
XY_GRID_RESOLUTION = 2.0 # [m]
25
28
YAW_GRID_RESOLUTION = np .deg2rad (15.0 ) # [rad]
26
29
MOTION_RESOLUTION = 0.1 # [m] path interporate resolution
27
- N_STEER = 20.0 # number of steer command
30
+ N_STEER = 20 # number of steer command
28
31
H_COST = 1.0
29
32
VR = 1.0 # robot radius
30
33
@@ -131,7 +134,8 @@ def __init__(self, ox, oy, xyreso, yawreso):
131
134
132
135
def calc_motion_inputs ():
133
136
134
- for steer in np .concatenate ((np .linspace (- MAX_STEER , MAX_STEER , N_STEER ),[0.0 ])):
137
+ for steer in np .concatenate ((np .linspace (- MAX_STEER , MAX_STEER ,
138
+ N_STEER ), [0.0 ])):
135
139
for d in [1 , - 1 ]:
136
140
yield [steer , d ]
137
141
@@ -225,7 +229,8 @@ def update_node_with_analystic_expantion(current, goal,
225
229
apath = analytic_expantion (current , goal , c , ox , oy , kdtree )
226
230
227
231
if apath :
228
- plt .plot (apath .x , apath .y )
232
+ if show_animation :
233
+ plt .plot (apath .x , apath .y )
229
234
fx = apath .x [1 :]
230
235
fy = apath .y [1 :]
231
236
fyaw = apath .yaw [1 :]
@@ -337,6 +342,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso):
337
342
current , ngoal , config , ox , oy , obkdtree )
338
343
339
344
if isupdated :
345
+ print ("path found" )
340
346
break
341
347
342
348
for neighbor in get_neighbors (current , config , ox , oy , obkdtree ):
@@ -437,12 +443,16 @@ def main():
437
443
start = [10.0 , 10.0 , np .deg2rad (90.0 )]
438
444
goal = [50.0 , 50.0 , np .deg2rad (- 90.0 )]
439
445
440
- plt .plot (ox , oy , ".k" )
441
- rs .plot_arrow (start [0 ], start [1 ], start [2 ], fc = 'g' )
442
- rs .plot_arrow (goal [0 ], goal [1 ], goal [2 ])
446
+ print ("start : " , start )
447
+ print ("goal : " , goal )
448
+
449
+ if show_animation :
450
+ plt .plot (ox , oy , ".k" )
451
+ rs .plot_arrow (start [0 ], start [1 ], start [2 ], fc = 'g' )
452
+ rs .plot_arrow (goal [0 ], goal [1 ], goal [2 ])
443
453
444
- plt .grid (True )
445
- plt .axis ("equal" )
454
+ plt .grid (True )
455
+ plt .axis ("equal" )
446
456
447
457
path = hybrid_a_star_planning (
448
458
start , goal , ox , oy , XY_GRID_RESOLUTION , YAW_GRID_RESOLUTION )
@@ -451,14 +461,15 @@ def main():
451
461
y = path .ylist
452
462
yaw = path .yawlist
453
463
454
- for ix , iy , iyaw in zip (x , y , yaw ):
455
- plt .cla ()
456
- plt .plot (ox , oy , ".k" )
457
- plt .plot (x , y , "-r" , label = "Hybrid A* path" )
458
- plt .grid (True )
459
- plt .axis ("equal" )
460
- plot_car (ix , iy , iyaw )
461
- plt .pause (0.0001 )
464
+ if show_animation :
465
+ for ix , iy , iyaw in zip (x , y , yaw ):
466
+ plt .cla ()
467
+ plt .plot (ox , oy , ".k" )
468
+ plt .plot (x , y , "-r" , label = "Hybrid A* path" )
469
+ plt .grid (True )
470
+ plt .axis ("equal" )
471
+ plot_car (ix , iy , iyaw )
472
+ plt .pause (0.0001 )
462
473
463
474
print (__file__ + " done!!" )
464
475
0 commit comments