Skip to content

Commit 89ef0a9

Browse files
committed
add bidirectional A*
1 parent 93e2116 commit 89ef0a9

File tree

1 file changed

+331
-0
lines changed

1 file changed

+331
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,331 @@
1+
"""
2+
3+
Bidirectional A* grid planning
4+
5+
author: Erwin Lejeune (@spida_rwin)
6+
7+
See Wikipedia article (https://en.wikipedia.org/wiki/Bidirectional_search)
8+
9+
"""
10+
11+
import math
12+
13+
import matplotlib.pyplot as plt
14+
15+
show_animation = True
16+
17+
18+
class BidirAStarPlanner:
19+
20+
def __init__(self, ox, oy, reso, rr):
21+
"""
22+
Initialize grid map for a star planning
23+
24+
ox: x position list of Obstacles [m]
25+
oy: y position list of Obstacles [m]
26+
reso: grid resolution [m]
27+
rr: robot radius[m]
28+
"""
29+
30+
self.reso = reso
31+
self.rr = rr
32+
self.calc_obstacle_map(ox, oy)
33+
self.motion = self.get_motion_model()
34+
35+
class Node:
36+
def __init__(self, x, y, cost, pind):
37+
self.x = x # index of grid
38+
self.y = y # index of grid
39+
self.cost = cost
40+
self.pind = pind
41+
42+
def __str__(self):
43+
return str(self.x) + "," + str(self.y) + "," + str(
44+
self.cost) + "," + str(self.pind)
45+
46+
def planning(self, sx, sy, gx, gy):
47+
"""
48+
Bidirectional A star path search
49+
50+
input:
51+
sx: start x position [m]
52+
sy: start y position [m]
53+
gx: goal x position [m]
54+
gy: goal y position [m]
55+
56+
output:
57+
rx: x position list of the final path
58+
ry: y position list of the final path
59+
"""
60+
61+
nstart = self.Node(self.calc_xyindex(sx, self.minx),
62+
self.calc_xyindex(sy, self.miny), 0.0, -1)
63+
ngoal = self.Node(self.calc_xyindex(gx, self.minx),
64+
self.calc_xyindex(gy, self.miny), 0.0, -1)
65+
66+
open_set_A, closed_set_A = dict(), dict()
67+
open_set_B, closed_set_B = dict(), dict()
68+
open_set_A[self.calc_grid_index(nstart)] = nstart
69+
open_set_B[self.calc_grid_index(ngoal)] = ngoal
70+
71+
current_A = nstart
72+
current_B = ngoal
73+
74+
while 1:
75+
if len(open_set_A) == 0:
76+
print("Open set A is empty..")
77+
break
78+
79+
if len(open_set_B) == 0:
80+
print("Open set B is empty..")
81+
break
82+
83+
c_id_A = min(
84+
open_set_A,
85+
key=lambda o: open_set_A[o].cost + self.calc_heuristic(current_B,
86+
open_set_A[
87+
o]))
88+
89+
current_A = open_set_A[c_id_A]
90+
91+
c_id_B = min(
92+
open_set_B,
93+
key=lambda o: open_set_B[o].cost + self.calc_heuristic(current_A,
94+
open_set_B[
95+
o]))
96+
97+
current_B = open_set_B[c_id_B]
98+
99+
# show graph
100+
if show_animation: # pragma: no cover
101+
plt.plot(self.calc_grid_position(current_A.x, self.minx),
102+
self.calc_grid_position(current_A.y, self.miny), "xc")
103+
plt.plot(self.calc_grid_position(current_B.x, self.minx),
104+
self.calc_grid_position(current_B.y, self.miny), "xc")
105+
# for stopping simulation with the esc key.
106+
plt.gcf().canvas.mpl_connect('key_release_event',
107+
lambda event: [exit(
108+
0) if event.key == 'escape' else None])
109+
if len(closed_set_A.keys()) % 10 == 0:
110+
plt.pause(0.001)
111+
112+
if current_A.x == current_B.x and current_A.y == current_B.y:
113+
print("Found goal")
114+
meetpointA = current_A
115+
meetpointB = current_B
116+
break
117+
118+
# Remove the item from the open set
119+
del open_set_A[c_id_A]
120+
del open_set_B[c_id_B]
121+
122+
# Add it to the closed set
123+
closed_set_A[c_id_A] = current_A
124+
closed_set_B[c_id_B] = current_B
125+
126+
# expand_grid search grid based on motion model
127+
for i, _ in enumerate(self.motion):
128+
node = self.Node(current_A.x + self.motion[i][0],
129+
current_A.y + self.motion[i][1],
130+
current_A.cost + self.motion[i][2], c_id_A)
131+
n_id = self.calc_grid_index(node)
132+
133+
# If the node is not safe, do nothing
134+
if not self.verify_node(node):
135+
continue
136+
137+
if n_id in closed_set_A:
138+
continue
139+
140+
if n_id not in open_set_A:
141+
open_set_A[n_id] = node # discovered a new node
142+
else:
143+
if open_set_A[n_id].cost > node.cost:
144+
# This path is the best until now. record it
145+
open_set_A[n_id] = node
146+
147+
for i, _ in enumerate(self.motion):
148+
node = self.Node(current_B.x + self.motion[i][0],
149+
current_B.y + self.motion[i][1],
150+
current_B.cost + self.motion[i][2], c_id_B)
151+
n_id = self.calc_grid_index(node)
152+
153+
# If the node is not safe, do nothing
154+
if not self.verify_node(node):
155+
continue
156+
157+
if n_id in closed_set_B:
158+
continue
159+
160+
if n_id not in open_set_B:
161+
open_set_B[n_id] = node # discovered a new node
162+
else:
163+
if open_set_B[n_id].cost > node.cost:
164+
# This path is the best until now. record it
165+
open_set_B[n_id] = node
166+
167+
rx, ry = self.calc_final_path_bidir(meetpointA, meetpointB, closed_set_A, closed_set_B)
168+
169+
return rx, ry
170+
171+
def calc_final_path_bidir(self, meetnode_A, meetnode_B, closed_set_A, closed_set_B):
172+
rx_A, ry_A = self.calc_final_path(meetnode_A, closed_set_A)
173+
rx_B, ry_B = self.calc_final_path(meetnode_B, closed_set_B)
174+
175+
rx_A.reverse()
176+
ry_A.reverse()
177+
178+
rx = rx_A + rx_B
179+
ry = ry_A + ry_B
180+
181+
return rx, ry
182+
183+
def calc_final_path(self, ngoal, closedset):
184+
# generate final course
185+
rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [
186+
self.calc_grid_position(ngoal.y, self.miny)]
187+
pind = ngoal.pind
188+
while pind != -1:
189+
n = closedset[pind]
190+
rx.append(self.calc_grid_position(n.x, self.minx))
191+
ry.append(self.calc_grid_position(n.y, self.miny))
192+
pind = n.pind
193+
194+
return rx, ry
195+
196+
@staticmethod
197+
def calc_heuristic(n1, n2):
198+
w = 1.0 # weight of heuristic
199+
d = w * math.hypot(n1.x - n2.x, n1.y - n2.y)
200+
return d
201+
202+
def calc_grid_position(self, index, minp):
203+
"""
204+
calc grid position
205+
206+
:param index:
207+
:param minp:
208+
:return:
209+
"""
210+
pos = index * self.reso + minp
211+
return pos
212+
213+
def calc_xyindex(self, position, min_pos):
214+
return round((position - min_pos) / self.reso)
215+
216+
def calc_grid_index(self, node):
217+
return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
218+
219+
def verify_node(self, node):
220+
px = self.calc_grid_position(node.x, self.minx)
221+
py = self.calc_grid_position(node.y, self.miny)
222+
223+
if px < self.minx:
224+
return False
225+
elif py < self.miny:
226+
return False
227+
elif px >= self.maxx:
228+
return False
229+
elif py >= self.maxy:
230+
return False
231+
232+
# collision check
233+
if self.obmap[node.x][node.y]:
234+
return False
235+
236+
return True
237+
238+
def calc_obstacle_map(self, ox, oy):
239+
240+
self.minx = round(min(ox))
241+
self.miny = round(min(oy))
242+
self.maxx = round(max(ox))
243+
self.maxy = round(max(oy))
244+
print("minx:", self.minx)
245+
print("miny:", self.miny)
246+
print("maxx:", self.maxx)
247+
print("maxy:", self.maxy)
248+
249+
self.xwidth = round((self.maxx - self.minx) / self.reso)
250+
self.ywidth = round((self.maxy - self.miny) / self.reso)
251+
print("xwidth:", self.xwidth)
252+
print("ywidth:", self.ywidth)
253+
254+
# obstacle map generation
255+
self.obmap = [[False for i in range(self.ywidth)]
256+
for i in range(self.xwidth)]
257+
for ix in range(self.xwidth):
258+
x = self.calc_grid_position(ix, self.minx)
259+
for iy in range(self.ywidth):
260+
y = self.calc_grid_position(iy, self.miny)
261+
for iox, ioy in zip(ox, oy):
262+
d = math.hypot(iox - x, ioy - y)
263+
if d <= self.rr:
264+
self.obmap[ix][iy] = True
265+
break
266+
267+
@staticmethod
268+
def get_motion_model():
269+
# dx, dy, cost
270+
motion = [[1, 0, 1],
271+
[0, 1, 1],
272+
[-1, 0, 1],
273+
[0, -1, 1],
274+
[-1, -1, math.sqrt(2)],
275+
[-1, 1, math.sqrt(2)],
276+
[1, -1, math.sqrt(2)],
277+
[1, 1, math.sqrt(2)]]
278+
279+
return motion
280+
281+
282+
def main():
283+
print(__file__ + " start!!")
284+
285+
# start and goal position
286+
sx = 10.0 # [m]
287+
sy = 10.0 # [m]
288+
gx = 50.0 # [m]
289+
gy = 50.0 # [m]
290+
grid_size = 2.0 # [m]
291+
robot_radius = 1.0 # [m]
292+
293+
# set obstable positions
294+
ox, oy = [], []
295+
for i in range(-10, 60):
296+
ox.append(i)
297+
oy.append(-10.0)
298+
for i in range(-10, 60):
299+
ox.append(60.0)
300+
oy.append(i)
301+
for i in range(-10, 61):
302+
ox.append(i)
303+
oy.append(60.0)
304+
for i in range(-10, 61):
305+
ox.append(-10.0)
306+
oy.append(i)
307+
for i in range(-10, 40):
308+
ox.append(20.0)
309+
oy.append(i)
310+
for i in range(0, 40):
311+
ox.append(40.0)
312+
oy.append(60.0 - i)
313+
314+
if show_animation: # pragma: no cover
315+
plt.plot(ox, oy, ".k")
316+
plt.plot(sx, sy, "og")
317+
plt.plot(gx, gy, "ob")
318+
plt.grid(True)
319+
plt.axis("equal")
320+
321+
bidir_a_star = BidirAStarPlanner(ox, oy, grid_size, robot_radius)
322+
rx, ry = bidir_a_star.planning(sx, sy, gx, gy)
323+
324+
if show_animation: # pragma: no cover
325+
plt.plot(rx, ry, "-r")
326+
plt.pause(.0001)
327+
plt.show()
328+
329+
330+
if __name__ == '__main__':
331+
main()

0 commit comments

Comments
 (0)