8-Puzzle Solver → Route Finding in Robotics

Why Search Algorithms?
Breadth-First Search (BFS) and Depth-First Search (DFS) are the bedrock of problem solving in AI. They teach you how to systematically explore a state space (all possible configurations of a problem) and recover a solution path. You’ll use the exact same ideas later for heuristic search (A*), constraint solvers, planning, and even within modern robotics stacks for pathfinding on occupancy grids.
What you’ll build today: (a) an 8-puzzle solver using BFS/DFS; (b) a grid route-finding demo, the building block for robotics navigation.
Search Algorithms
1. State spaces, nodes, and operators
A state describes a configuration (e.g., a 3×3 board permutation in the 8-puzzle, or a robot’s $(x,y)$ cell on a grid).
Operators (actions) move you from one state to another (swap the blank tile up/down/left/right; move the robot to a neighboring free cell).
A path is a sequence of actions from start to goal.
2. Search tree vs. graph search
Tree search: expands states without remembering visited ones; risks exponential revisitation.
Graph search: maintains a visited/explored set to avoid cycles and repeated work. Almost always preferred for finite spaces.
3. Breadth-First Search (BFS)
Explores the shallowest nodes first using a FIFO queue.
On unweighted graphs (every step costs the same), BFS is complete and optimal—it finds the shortest path in number of steps.
Time complexity: where
is branching factor and
is the shallowest goal depth.
Space complexity: also (stores frontier + explored at the same breadth).
When to use: shortest path on unweighted graphs/grids; small to moderate depth problems.
4. Depth-First Search (DFS)
Explores along a path as deep as possible using a stack (or recursion), then backtracks.
Time complexity: where
is maximum depth; space complexity:
(much smaller than BFS).
Completeness: not guaranteed in infinite-depth spaces (can get stuck going deep).
Optimality: not optimal (may return a longer path than necessary).
When to use: memory-constrained settings; when any solution suffices and deep solutions are likely.
5. Practical variants you’ll meet soon
Iterative Deepening DFS (IDDFS): combines low memory usage of DFS with completeness/optimality (in unit cost settings) by deepening the limit:
Bidirectional search: search forward from start and backward from goal; often reduces complexity from to
in practice.
Heuristic search (A):* prioritizes nodes using ; with admissible
, A* is optimal and dramatically prunes the state space.
6. 8-puzzle specifics (for today’s toy problem)
There are tile permutations, but only half are reachable from a given goal due to parity; thus reachable states
.
A configuration is solvable iff its inversion count parity matches the goal’s. An inversion is a pair of tiles with
but tile
appears after tile
in the flattened list (ignoring the blank).
BFS is great for finding the shortest move sequence; DFS can quickly find a sequence (not necessarily shortest).
Toy Problem – 8-Puzzle Solver (BFS & DFS)
We’ll represent the 3×3 board as a length-9 tuple with 0 as the blank:
Dataset Snapshot (Representation)
Goal: Example start (solvable):
(1,2,3, (1,2,3,
4,5,6, 4,5,6,
7,8,0) 0,7,8)
Actions: move the blank 0 up/down/left/right when legal.
State space: neighbors are states produced by swapping 0 with an adjacent tile.
1 – Utilities: neighbors, solvability, and path reconstruction
Step 1: Imports and goal definition
Use Python’s deque for queues later; define the canonical goal state for the 8-puzzle.
from collections import deque
# 8-puzzle goal configuration: 0 denotes the blank tile.
GOAL = (1, 2, 3,
4, 5, 6,
7, 8, 0)
Step 2: Index helpers (flat index ↔ row/col)
These tiny helpers convert between the flat 0–8 index and (row, col) in a 3×3 grid—handy for legal-move checks.
def index_to_rc(i):
"""Map flat index [0..8] -> (row, col) in a 3x3 grid."""
return divmod(i, 3)
def rc_to_index(r, c):
"""Map (row, col) -> flat index [0..8] in a 3x3 grid."""
return r * 3 + c
Step 3: Neighbor generator (legal moves)
Given a state (a tuple of 9 ints with 0 as blank), yield next states by sliding the blank up/down/left/right when possible—each with its action label.
def neighbors(state):
"""
Generate (next_state, action) for all legal blank moves.
action in {"Up","Down","Left","Right"} describes the blank's motion.
"""
i0 = state.index(0) # blank position
r, c = index_to_rc(i0)
moves = []
for dr, dc, action in [(-1, 0, "Up"), (1, 0, "Down"),
(0, -1, "Left"), (0, 1, "Right")]:
nr, nc = r + dr, c + dc
if 0 <= nr < 3 and 0 <= nc < 3:
j = rc_to_index(nr, nc) # tile to swap with blank
new_state = list(state)
new_state[i0], new_state[j] = new_state[j], new_state[i0]
moves.append((tuple(new_state), action))
return moves
4. Path reconstruction (states + actions)
After search fills parent and action maps, rebuild the full sequence of states and the aligned action list from start→goal.
def reconstruct_path(parent, action, goal_state):
"""
Reconstruct (path_states, path_actions) from parent/action maps.
- parent[s] = predecessor state or None for the start
- action[s] = action taken to reach s from parent[s] (None for start)
"""
# Rebuild states
path_states = []
s = goal_state
while s is not None:
path_states.append(s)
s = parent[s]
path_states.reverse()
# Rebuild actions (aligned with transitions path_states[0]->...->path_states[-1])
path_actions = []
s = goal_state
while s is not None and action[s] is not None:
path_actions.append(action[s])
s = parent[s]
path_actions.reverse()
return path_states, path_actions
5. Inversion count (parity test ingredient)
Count out-of-order tile pairs ignoring the blank; used to determine solvability parity for the 8-puzzle.
def inversion_count(state):
"""
Count inversions: pairs (i,j) with i<j but state[i] > state[j], ignoring 0.
"""
arr = [x for x in state if x != 0]
inv = 0
for i in range(len(arr)):
for j in range(i + 1, len(arr)):
if arr[i] > arr[j]:
inv += 1
return inv
6. Solvability check (8-puzzle)
A start state is solvable iff its inversion parity matches the goal’s inversion parity (for 3×3 with blank allowed anywhere).
def is_solvable(state, goal=GOAL):
"""
8-puzzle solvable iff inversion parity matches the goal's parity.
"""
return inversion_count(state) % 2 == inversion_count(goal) % 2
2 – Breadth-First Search (BFS)
1. Function signature & early exits
Check for trivial success and solvability before doing any work.
def bfs(start, goal=GOAL):
"""
Breadth-First Search on the 8-puzzle state space.
Returns (path_states, path_actions) for a shortest solution (unit-cost),
or None if unsolvable or not found.
"""
if start == goal:
return [start], []
if not is_solvable(start, goal):
return None
2. Frontier (queue) and bookkeeping
Use a FIFO queue; track parents and actions for reconstruction; keep a visited set to avoid repeats.
from collections import deque
q = deque([start]) # FIFO frontier
parent = {start: None}
action = {start: None}
visited = {start}
3. Main BFS loop (level-order expansion)
Pop from the left, expand neighbors, and enqueue unseen states.
while q:
s = q.popleft()
for ns, a in neighbors(s):
if ns not in visited:
visited.add(ns)
parent[ns] = s
action[ns] = a
4. Goal test and path reconstruction
As soon as we discover the goal, rebuild and return the shortest path.
if ns == goal:
return reconstruct_path(parent, action, ns)
q.append(ns)
5. No solution found (shouldn’t happen for solvable states)
Return None if the queue empties without success.
return None
3 – Depth-First Search with Depth Limit (DFS-limited)
3.1. Function signature & early exits
Same quick checks; a depth limit prevents infinite descent.
def dfs_limited(start, goal=GOAL, max_depth=30):
"""
Depth-First Search with a depth bound.
Returns (path_states, path_actions) if a solution is found within max_depth,
else None. Not guaranteed shortest, but uses low memory.
"""
if start == goal:
return [start], []
if not is_solvable(start, goal):
return None
3.2. Frontier (stack) and lightweight memory
Use an explicit stack to avoid recursion depth issues. Track the best-known depth per state to allow beneficial revisits.
stack = [(start, 0)] # (state, depth)
parent = {start: None}
action = {start: None}
visited_depth = {start: 0} # state -> shallowest depth discovered
3.3. Main DFS loop (deepening within limit)
Pop from the stack (LIFO), check goal, then push neighbors if within the depth cap.
while stack:
s, d = stack.pop()
if s == goal:
return reconstruct_path(parent, action, s)
if d < max_depth:
# reversed neighbor order to mimic recursive DFS (optional)
for ns, a in reversed(neighbors(s)):
nd = d + 1
3.4. Prune worse revisits; record parents/actions; push deeper
Only proceed if we’ve never seen ns or we’ve found a shallower route to it.
if ns not in visited_depth or nd < visited_depth[ns]:
visited_depth[ns] = nd
parent[ns] = s
action[ns] = a
stack.append((ns, nd))
3.5. No solution within the depth limit
If the stack empties, either no solution exists within max_depth or the instance is very deep.
return None
4 – Run the Demo
What this does: solves a simple starting position with both BFS and limited DFS and prints the move count with action sequence.
if __name__ == "__main__":
start = (1,2,3,4,5,6,0,7,8) # easy solvable example
out_bfs = bfs(start)
if out_bfs is not None:
states, actions = out_bfs
print(f"BFS: moves={len(actions)}, actions={actions}")
else:
print("BFS: Unsolvable or not found.")
out_dfs = dfs_limited(start, max_depth=30)
if out_dfs is not None:
states, actions = out_dfs
print(f"DFS (limited): moves={len(actions)}, actions={actions}")
else:
print("DFS: Not found within depth.")
Quick Reference: Full 8-puzzle Code
from collections import deque
GOAL = (1,2,3,4,5,6,7,8,0)
def index_to_rc(i): return divmod(i, 3)
def rc_to_index(r, c): return r*3 + c
def neighbors(state):
i0 = state.index(0)
r, c = index_to_rc(i0)
moves = []
for dr, dc, action in [(-1,0,"Up"), (1,0,"Down"), (0,-1,"Left"), (0,1,"Right")]:
nr, nc = r+dr, c+dc
if 0 <= nr < 3 and 0 <= nc < 3:
j = rc_to_index(nr, nc)
new_state = list(state)
new_state[i0], new_state[j] = new_state[j], new_state[i0]
moves.append((tuple(new_state), action))
return moves
def reconstruct_path(parent, action, goal_state):
path_states, path_actions = [], []
s = goal_state
while s is not None:
path_states.append(s)
s = parent[s]
path_states.reverse()
s = goal_state
while s is not None and action[s] is not None:
path_actions.append(action[s])
s = parent[s]
path_actions.reverse()
return path_states, path_actions
def inversion_count(state):
arr = [x for x in state if x != 0]
inv = 0
for i in range(len(arr)):
for j in range(i+1, len(arr)):
if arr[i] > arr[j]: inv += 1
return inv
def is_solvable(state, goal=GOAL):
return inversion_count(state) % 2 == inversion_count(goal) % 2
def bfs(start, goal=GOAL):
if start == goal: return [start], []
if not is_solvable(start, goal): return None
q = deque([start])
parent = {start: None}
action = {start: None}
visited = {start}
while q:
s = q.popleft()
for ns, a in neighbors(s):
if ns not in visited:
visited.add(ns)
parent[ns] = s
action[ns] = a
if ns == goal:
return reconstruct_path(parent, action, ns)
q.append(ns)
return None
def dfs_limited(start, goal=GOAL, max_depth=30):
if start == goal: return [start], []
if not is_solvable(start, goal): return None
stack = [(start, 0)]
parent = {start: None}
action = {start: None}
visited_depth = {start: 0}
while stack:
s, d = stack.pop()
if s == goal: return reconstruct_path(parent, action, s)
if d < max_depth:
for ns, a in reversed(neighbors(s)):
nd = d+1
if ns not in visited_depth or nd < visited_depth[ns]:
visited_depth[ns] = nd
parent[ns] = s
action[ns] = a
stack.append((ns, nd))
return None
Real‑World Application — Route Finding in Robotics (Grid BFS/DFS)
We’ll model a robot moving on a 2D occupancy grid. Each free cell has unit cost; obstacles are blocked.
- BFS → shortest number of steps from start to goal (in 4-connected grids).
- DFS → any reachable path (not necessarily shortest); small memory footprint.
Step 1: Grid representation & neighbors
What this does: encodes a small map with obstacles and defines legal 4-connected moves.
from collections import deque
FREE, BLOCK = 0, 1
grid = [
[0,0,0,0,0,0,0,1,0,0],
[0,1,1,1,0,0,0,1,0,0],
[0,0,0,1,0,1,0,0,0,0],
[0,1,0,0,0,1,0,1,1,0],
[0,1,0,1,0,0,0,0,1,0],
[0,0,0,1,0,1,1,0,0,0],
[1,1,0,0,0,0,0,1,0,0],
[0,0,0,1,1,0,0,0,0,0],
]
start = (0, 0) # (row, col)
goal = (7, 9)
def in_bounds(r, c):
return 0 <= r < len(grid) and 0 <= c < len(grid[0])
def grid_neighbors(r, c):
for dr, dc, action in [(-1,0,"Up"), (1,0,"Down"), (0,-1,"Left"), (0,1,"Right")]:
nr, nc = r+dr, c+dc
if in_bounds(nr, nc) and grid[nr][nc] == FREE:
yield (nr, nc), action
Step 2: BFS for shortest path
What this does: uses a queue to expand cells by distance and reconstructs the shortest path when the goal is reached.
def bfs_grid(start, goal):
if start == goal:
return [start], []
q = deque([start])
parent = {start: None}
action = {start: None}
visited = {start}
while q:
r, c = q.popleft()
for (nr, nc), a in grid_neighbors(r, c):
nxt = (nr, nc)
if nxt not in visited:
visited.add(nxt)
parent[nxt] = (r, c)
action[nxt] = a
if nxt == goal:
# reconstruct
path, acts = [], []
s = nxt
while s is not None:
path.append(s)
s = parent[s]
path.reverse()
s = nxt
while s is not None and action[s] is not None:
acts.append(action[s])
s = parent[s]
acts.reverse()
return path, acts
q.append(nxt)
return None
Step 3: DFS (any path)
What this does: explores deeply first with a depth cap; returns any discovered route.
def dfs_grid(start, goal, max_depth=512):
stack = [(start, 0)]
parent = {start: None}
action = {start: None}
visited_depth = {start: 0}
while stack:
(r, c), d = stack.pop()
if (r, c) == goal:
# reconstruct
path, acts = [], []
s = (r, c)
while s is not None:
path.append(s)
s = parent[s]
path.reverse()
s = (r, c)
while s is not None and action[s] is not None:
acts.append(action[s])
s = parent[s]
acts.reverse()
return path, acts
if d < max_depth:
for (nr, nc), a in reversed(list(grid_neighbors(r, c))):
nd = d + 1
if (nr, nc) not in visited_depth or nd < visited_depth[(nr, nc)]:
visited_depth[(nr, nc)] = nd
parent[(nr, nc)] = (r, c)
action[(nr, nc)] = a
stack.append(((nr, nc), nd))
return None
Step 4: Run the robotics demo
What this does: finds a shortest route (BFS), prints the steps and a simple ASCII map; also attempts a DFS path.
def render_path_on_grid(path):
g = [row[:] for row in grid]
for r, c in path:
if (r, c) not in (start, goal):
g[r][c] = 2 # mark path
# Simple ASCII renderer
legend = {0:'.', 1:'#', 2:'*'}
for r in range(len(g)):
line = ''.join(legend[x] for x in g[r])
print(line)
if __name__ == "__main__":
out = bfs_grid(start, goal)
if out:
path, acts = out
print(f"BFS shortest length = {len(path)-1}, actions = {acts}")
render_path_on_grid(path)
else:
print("No BFS path found.")
out2 = dfs_grid(start, goal, max_depth=1024)
if out2:
path, acts = out2
print(f"DFS path length = {len(path)-1}, actions = {acts}")
else:
print("No DFS path found.")
Quick Reference: Full Grid Pathfinding Code
from collections import deque
FREE, BLOCK = 0, 1
grid = [
[0,0,0,0,0,0,0,1,0,0],
[0,1,1,1,0,0,0,1,0,0],
[0,0,0,1,0,1,0,0,0,0],
[0,1,0,0,0,1,0,1,1,0],
[0,1,0,1,0,0,0,0,1,0],
[0,0,0,1,0,1,1,0,0,0],
[1,1,0,0,0,0,0,1,0,0],
[0,0,0,1,1,0,0,0,0,0],
]
start, goal = (0,0), (7,9)
def in_bounds(r, c): return 0 <= r < len(grid) and 0 <= c < len(grid[0])
def grid_neighbors(r, c):
for dr, dc, a in [(-1,0,"Up"), (1,0,"Down"), (0,-1,"Left"), (0,1,"Right")]:
nr, nc = r+dr, c+dc
if in_bounds(nr, nc) and grid[nr][nc] == FREE:
yield (nr, nc), a
def bfs_grid(start, goal):
if start == goal: return [start], []
q = deque([start])
parent = {start: None}
action = {start: None}
visited = {start}
while q:
r, c = q.popleft()
for (nr, nc), a in grid_neighbors(r, c):
nxt = (nr, nc)
if nxt not in visited:
visited.add(nxt)
parent[nxt] = (r, c)
action[nxt] = a
if nxt == goal:
path, acts = [], []
s = nxt
while s is not None:
path.append(s)
s = parent[s]
path.reverse()
s = nxt
while s is not None and action[s] is not None:
acts.append(action[s])
s = parent[s]
acts.reverse()
return path, acts
q.append(nxt)
return None
def dfs_grid(start, goal, max_depth=512):
stack = [(start, 0)]
parent = {start: None}
action = {start: None}
visited_depth = {start: 0}
while stack:
(r, c), d = stack.pop()
if (r, c) == goal:
path, acts = [], []
s = (r, c)
while s is not None:
path.append(s)
s = parent[s]
path.reverse()
s = (r, c)
while s is not None and action[s] is not None:
acts.append(action[s])
s = parent[s]
acts.reverse()
return path, acts
if d < max_depth:
for (nr, nc), a in reversed(list(grid_neighbors(r, c))):
nd = d+1
if (nr, nc) not in visited_depth or nd < visited_depth[(nr, nc)]:
visited_depth[(nr, nc)] = nd
parent[(nr, nc)] = (r, c)
action[(nr, nc)] = a
stack.append(((nr, nc), nd))
return None
def render_path_on_grid(path):
g = [row[:] for row in grid]
for r, c in path:
if (r, c) not in (start, goal):
g[r][c] = 2
legend = {0:'.', 1:'#', 2:'*'}
for r in range(len(g)):
print(''.join(legend[x] for x in g[r]))
if __name__ == "__main__":
out = bfs_grid(start, goal)
if out:
path, acts = out
print(f"BFS shortest length = {len(path)-1}, actions = {acts}")
render_path_on_grid(path)
else:
print("No BFS path found.")
out2 = dfs_grid(start, goal, max_depth=1024)
if out2:
path, acts = out2
print(f"DFS path length = {len(path)-1}, actions = {acts}")
Strengths & Limitations
Strengths
- BFS: complete and optimal on unit-cost graphs; simple to implement; ideal for shortest paths on grids.
- DFS: tiny memory footprint; returns a path quickly if deep solutions exist; easy to implement recursively or iteratively.
- Both: foundational—build intuition for advanced methods (IDDFS, A*, D*, RRT, etc.).
Limitations
- BFS: memory-hungry (
), can become infeasible at larger depths.
- DFS: not optimal; can fail to terminate in infinite or cyclic spaces without careful handling (limits/visited).
- Both (uninformed): ignore problem-specific guidance; scale poorly versus informed (heuristic) search.
Final Notes
You learned how to model problems as search over states, apply BFS to guarantee shortest paths on unit-cost spaces, and use DFS to find any feasible route with minimal memory. You implemented both an 8-puzzle solver and a robotics-style grid pathfinder.
These patterns directly transfer to more advanced planning and navigation algorithms and prepare you to add heuristics (A*), dynamic replanning (D*), or sampling-based planners—core tools in modern AI and robotics.
Next Steps for You:
Add heuristics: implement A* for the 8-puzzle using number of misplaced tiles and
Manhattan distance; compare node expansions vs. BFS.
Scale the environment: switch the grid to an image-based occupancy map (e.g., PNG → grid), then compare BFS vs. A* with a Euclidean/Manhattan heuristic.
(Optional) Try IDDFS and bidirectional BFS on the 8-puzzle and measure empirical speedups.
References
[1] S. J. Russell and P. Norvig, Artificial Intelligence: A Modern Approach, 4th ed. Hoboken, NJ, USA: Pearson, 2020.
[2] R. E. Korf, “Depth-first iterative-deepening: An optimal admissible tree search,” Artificial Intelligence, vol. 27, no. 1, pp. 97–109, 1985.
[3] P. E. Hart, N. J. Nilsson, and B. Raphael, “A formal basis for the heuristic determination of minimum cost paths,” IEEE Transactions on Systems Science and Cybernetics, vol. 4, no. 2, pp. 100–107, 1968.
[4] J. Pearl, Heuristics: Intelligent Search Strategies for Computer Problem Solving. Boston, MA, USA: Addison-Wesley, 1984.
[5] R. E. Korf, “Finding optimal solutions to Rubik’s Cube using pattern databases,” AAAI, pp. 700–705, 1997; and related work on the 15/24-puzzle.
[6] S. M. LaValle, Planning Algorithms. Cambridge, U.K.: Cambridge Univ. Press, 2006.
[7] T. H. Cormen, C. E. Leiserson, R. L. Rivest, and C. Stein, Introduction to Algorithms, 3rd ed. Cambridge, MA, USA: MIT Press, 2009.

Leave a comment