The A* Algorithm
Dijkstra’s algorithm is very much related to the Uniform Cost Search algorithm and in fact logically they are equivalent as the algorithm explores uniformly all nodes that have the same PastCost.
In the A* algorithm, we start using the fact that we know the end state and therefore attempt to find methods that bias the exploration towards it. A* uses both \(C^*(s)\) and an estimate of the optimal Cost-to-go or FutureCost \(G^*(s)\) because obviously to know exactly \(G^*(s)\) is equivalent to solving the original search problem. Therefore the metric for prioritizing the Q queue is:
\[C^*(s) + h(s)\]
If \(h(s)\) is an underestimate of the \(G^*(s)\) the Astar algorithm is guaranteed to fine optimal plans.
Route planner example
In the figure above we are given the graph of the romanian roadnetwork and asked to find the best route from Arad to Bucharest. Note that for applying A* to more realistic example, you can use the Open Street Maps project and associated python libraries to produce much larger networks where the nodes may be cities or intersectionr or any other OSM tag (attribute).
For \(h(s)\) we use the straightline distance heuristic, which we will call hSLD . If the goal is Bucharest, we need to know the straight-line distances to Bucharest, which are shown below for all nodes in the graph.
Notice that the values of \(h(s)\) cannot be computed from the problem description itself. Moreover, it takes a certain amount of experience to know that \(h(s)\) is correlated with actual road distances and is, therefore, a useful heuristic. Observe how the A* algorithm behaves when using the heuristic \(h(s)\) in the following figure.
Robotics example
A stand-alone A* planner in python is shown next. Its instructive to go through the code to understand how it works.
import math
import matplotlib.pyplot as plt
= True
show_animation
class AStarPlanner:
def __init__(self, ox, oy, reso, rr):
"""
Initialize grid map for a star planning
ox: x position list of Obstacles [m]
oy: y position list of Obstacles [m]
reso: grid resolution [m]
rr: robot radius[m]
"""
self.reso = reso
self.rr = rr
self.calc_obstacle_map(ox, oy)
self.motion = self.get_motion_model()
class Node:
def __init__(self, x, y, cost, pind):
self.x = x # index of grid
self.y = y # index of grid
self.cost = cost
self.pind = pind
def __str__(self):
return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind)
def planning(self, sx, sy, gx, gy):
"""
A star path search
input:
sx: start x position [m]
sy: start y position [m]
gx: goal x position [m]
gx: goal x position [m]
output:
rx: x position list of the final path
ry: y position list of the final path
"""
= self.Node(self.calc_xyindex(sx, self.minx),
nstart self.calc_xyindex(sy, self.miny), 0.0, -1)
= self.Node(self.calc_xyindex(gx, self.minx),
ngoal self.calc_xyindex(gy, self.miny), 0.0, -1)
= dict(), dict()
open_set, closed_set
# populate the frontier (open set) with the starting node
self.calc_grid_index(nstart)] = nstart
open_set[
while 1:
if len(open_set) == 0:
print("Open set is empty..")
break
= min(
c_id =lambda o: open_set[o].cost + self.calc_heuristic(ngoal, open_set[o]))
open_set, key= open_set[c_id]
current
# show graph
if show_animation: # pragma: no cover
self.calc_grid_position(current.x, self.minx),
plt.plot(self.calc_grid_position(current.y, self.miny), "xc")
# for stopping simulation with the esc key.
'key_release_event',
plt.gcf().canvas.mpl_connect(lambda event: [exit(0) if event.key == 'escape' else None])
if len(closed_set.keys()) % 10 == 0:
0.001)
plt.pause(
if current.x == ngoal.x and current.y == ngoal.y:
print("Find goal")
= current.pind
ngoal.pind = current.cost
ngoal.cost break
# Remove the item from the open set
del open_set[c_id]
# Add it to the closed set
= current
closed_set[c_id]
# expand_grid search grid based on motion model
for i, _ in enumerate(self.motion):
= self.Node(current.x + self.motion[i][0],
node + self.motion[i][1],
current.y + self.motion[i][2], c_id)
current.cost = self.calc_grid_index(node)
n_id
# If the node is not safe, do nothing
if not self.verify_node(node):
continue
if n_id in closed_set:
continue
if n_id not in open_set:
= node # discovered a new node
open_set[n_id] else:
if open_set[n_id].cost > node.cost:
# This path is the best until now. record it
= node
open_set[n_id]
= self.calc_final_path(ngoal, closed_set)
rx, ry
return rx, ry
def calc_final_path(self, ngoal, closedset):
# generate final course
= [self.calc_grid_position(ngoal.x, self.minx)], [
rx, ry self.calc_grid_position(ngoal.y, self.miny)]
= ngoal.pind
pind while pind != -1:
= closedset[pind]
n self.calc_grid_position(n.x, self.minx))
rx.append(self.calc_grid_position(n.y, self.miny))
ry.append(= n.pind
pind
return rx, ry
@staticmethod
def calc_heuristic(n1, n2):
= 1.0 # weight of heuristic
w = w * math.hypot(n1.x - n2.x, n1.y - n2.y)
d return d
def calc_grid_position(self, index, minp):
"""
calc grid position
:param index:
:param minp:
:return:
"""
= index * self.reso + minp
pos return pos
def calc_xyindex(self, position, min_pos):
return round((position - min_pos) / self.reso)
def calc_grid_index(self, node):
return (node.y - self.miny) * self.xwidth + (node.x - self.minx)
def verify_node(self, node):
= self.calc_grid_position(node.x, self.minx)
px = self.calc_grid_position(node.y, self.miny)
py
if px < self.minx:
return False
elif py < self.miny:
return False
elif px >= self.maxx:
return False
elif py >= self.maxy:
return False
# collision check
if self.obmap[node.x][node.y]:
return False
return True
def calc_obstacle_map(self, ox, oy):
# map limits
self.minx = round(min(ox))
self.miny = round(min(oy))
self.maxx = round(max(ox))
self.maxy = round(max(oy))
print("minx:", self.minx)
print("miny:", self.miny)
print("maxx:", self.maxx)
print("maxy:", self.maxy)
self.xwidth = round((self.maxx - self.minx) / self.reso)
self.ywidth = round((self.maxy - self.miny) / self.reso)
print("xwidth:", self.xwidth)
print("ywidth:", self.ywidth)
# obstacle map generation
self.obmap = [[False for i in range(self.ywidth)]
for i in range(self.xwidth)]
for ix in range(self.xwidth):
= self.calc_grid_position(ix, self.minx)
x for iy in range(self.ywidth):
= self.calc_grid_position(iy, self.miny)
y for iox, ioy in zip(ox, oy):
= math.hypot(iox - x, ioy - y)
d if d <= self.rr:
self.obmap[ix][iy] = True
break
@staticmethod
def get_motion_model():
# dx, dy, cost
= [[1, 0, 1],
motion 0, 1, 1],
[-1, 0, 1],
[0, -1, 1],
[-1, -1, math.sqrt(2)],
[-1, 1, math.sqrt(2)],
[1, -1, math.sqrt(2)],
[1, 1, math.sqrt(2)]]
[
return motion
def main():
print(__file__ + " start!!")
# start and goal position
= 10.0 # [m]
sx = 10.0 # [m]
sy = 50.0 # [m]
gx = 50.0 # [m]
gy = 2.0 # [m]
grid_size = 1.0 # [m]
robot_radius
# set obstable positions
= [], []
ox, oy for i in range(-10, 60):
ox.append(i)-10.0)
oy.append(for i in range(-10, 60):
60.0)
ox.append(
oy.append(i)for i in range(-10, 61):
ox.append(i)60.0)
oy.append(for i in range(-10, 61):
-10.0)
ox.append(
oy.append(i)for i in range(-10, 40):
20.0)
ox.append(
oy.append(i)for i in range(0, 40):
40.0)
ox.append(60.0 - i)
oy.append(
if show_animation: # pragma: no cover
".k")
plt.plot(ox, oy, "og")
plt.plot(sx, sy, "xb")
plt.plot(gx, gy, True)
plt.grid("equal")
plt.axis(
= AStarPlanner(ox, oy, grid_size, robot_radius)
a_star = a_star.planning(sx, sy, gx, gy)
rx, ry
if show_animation: # pragma: no cover
"-r")
plt.plot(rx, ry,
plt.show()
if __name__ == '__main__':
main()
Executing the code above results in the animation:
Animation of the A* algorithm - from here
This is excellent overview on how the principles of shortest path algorithms are applied in everyday applications such as Google maps directions. Practical implementation considerations are discussed for multi-modal route finding capabilities where the agent needs to find optimal routes while traversing multiple modes of transportation.