Imagine dropping a robot into an unfamiliar space. No map, no pre-programming. How does it figure out where to go next? Instructing a machine to build up a map from scratch, making intelligent decisions along the way, is what drives frontier-based exploration. This post, breaks down one of the most common strategies to that problem, and walks through the key ideas and concepts behind the Wavefront Frontier Detector algorithm [2]. We’ll also take a high-level look at a working Python implementation compatible with ROS at the end. 🔭 What do we mean by “Exploration”? What do we mean by “Exploration”? In Robotics, exploration is typically the robot’s first interaction it has with its environment. The robot systematically discovers and maps its surroundings by collecting data and gradually developing a map. During this process, the robot builds context for navigation that enables it to perform subsequent tasks in that space. When done autonomously, this process means the robot chooses where to go next based purely on what it has already seen. This is referred to as a frontier-based approach, which is a concept that dates as far back as 1997 [1]. 🧱 What is a frontier? What is a frontier? Frontiers are nothing but cells or regions on the boundary between the unexplored and explored spaces. They are essentially the “edge” of what the robot knows about its environment and does not. By systematically moving to frontiers, robots can efficiently “exhaust the frontiers” and explore new areas while building a map. on the boundary between the unexplored and explored on the boundary between the unexplored and explored Let us get clarity on some terminology here: Unknown: Region not yet explored by the robot’s sensors. Known: Already explored/known by the robot. Free Space: Known region without obstacles. Occupied Space: Known region with obstacles. Occupancy Grid: Grid representation of the environment where each cell holds an occupancy probability indicating whether it is free/occupied/unknown. Frontier: The boundary between known and unknown region. Unknown: Region not yet explored by the robot’s sensors. Unknown: Known: Already explored/known by the robot. Known: Free Space: Known region without obstacles. Free Space: Occupied Space: Known region with obstacles. Occupied Space: Occupancy Grid: Grid representation of the environment where each cell holds an occupancy probability indicating whether it is free/occupied/unknown. Occupancy Grid: Frontier: The boundary between known and unknown region. Frontier: In short, frontiers are the most informative next steps, so the goal is to build algorithms that find and prioritize them. frontiers are the most informative next steps 💻 Implementation: Implementation: Below I provide an ROS compatible Python implementation of the WFD algorithm [2] for autonomous robot exploration. The algorithm uses a 2 level Breadth First Search (BFS) graph traversal strategy: an outer BFS to scan the map and identify candidate frontiers, and an inner BFS to group connected frontier cells into frontier clusters. This implementation enables autonomous robot exploration by enabling it to efficiently explore unknown environments by progressively exhausting all frontiers until the entire map is fully built. Core algorithm: Core algorithm: def WFD(occupancy_grid, robot_position): """ Wavefront Frontier Detector Algorithm Inputs: - occupancy_grid: 2D grid representing the environment (UNKNOWN, FREE, OCCUPIED) - robot_position: Current position of the robot in the grid Returns: - all_frontiers: List of all detected frontiers """ map_open_list = set() map_close_list = set() frontier_open_list = set() frontier_close_list = set() queue_m = Queue() queue_m.enqueue(robot_position) map_open_list.add(robot_position) all_frontiers = [] # Outer BFS to find frontier cells while not queue_m.is_empty(): cell = queue_m.dequeue() map_open_list.remove(cell) map_close_list.add(cell) # Check if this cell is a frontier cell if is_frontier(cell, occupancy_grid): new_frontier = [] queue_f = Queue() queue_f.enqueue(cell) frontier_open_list.add(cell) # Inner BFS to extract the complete frontier cluster while not queue_f.is_empty(): frontier_cell = queue_f.dequeue() frontier_open_list.remove(frontier_cell) frontier_close_list.add(frontier_cell) if is_frontier(frontier_cell, occupancy_grid): new_frontier.append(frontier_cell) # Check neighbors in inner BFS for neighbor in get_neighbors(frontier_cell): if (neighbor not in map_close_list and neighbor not in frontier_open_list and neighbor not in frontier_close_list and is_valid_cell(neighbor, occupancy_grid)): queue_f.enqueue(neighbor) frontier_open_list.add(neighbor) if new_frontier: all_frontiers.append(new_frontier) # Continue outer BFS for neighbor in get_neighbors(cell): if (neighbor not in map_open_list and neighbor not in map_close_list and has_free_neighbor(neighbor, occupancy_grid)): queue_m.enqueue(neighbor) map_open_list.add(neighbor) return all_frontiers # Main call for the WFD autonomous exploration algorithm. def exploration(): while not rospy.is_shutdown(): current_map = get_occupancy_grid() robot_position = get_robot_position() # Calculate frontiers using WFD algorithm frontiers = WFD(current_map, robot_position) if not frontiers: rospy.loginfo("Exploration complete - no more frontiers") break # Calculate median points of each frontier cluster frontier_medians = [] for frontier in frontiers: median_point = calculate_median(frontier) frontier_medians.append(median_point) # Sort by distance to robot frontier_medians.sort(key=lambda point: distance(point, robot_position)) # Navigate to the closest frontier cluster for target in frontier_medians: if plan_path_to_point(target): move_to_point(target) # On arrival, perform complete sensor scan perform_scan() break save_map() def WFD(occupancy_grid, robot_position): """ Wavefront Frontier Detector Algorithm Inputs: - occupancy_grid: 2D grid representing the environment (UNKNOWN, FREE, OCCUPIED) - robot_position: Current position of the robot in the grid Returns: - all_frontiers: List of all detected frontiers """ map_open_list = set() map_close_list = set() frontier_open_list = set() frontier_close_list = set() queue_m = Queue() queue_m.enqueue(robot_position) map_open_list.add(robot_position) all_frontiers = [] # Outer BFS to find frontier cells while not queue_m.is_empty(): cell = queue_m.dequeue() map_open_list.remove(cell) map_close_list.add(cell) # Check if this cell is a frontier cell if is_frontier(cell, occupancy_grid): new_frontier = [] queue_f = Queue() queue_f.enqueue(cell) frontier_open_list.add(cell) # Inner BFS to extract the complete frontier cluster while not queue_f.is_empty(): frontier_cell = queue_f.dequeue() frontier_open_list.remove(frontier_cell) frontier_close_list.add(frontier_cell) if is_frontier(frontier_cell, occupancy_grid): new_frontier.append(frontier_cell) # Check neighbors in inner BFS for neighbor in get_neighbors(frontier_cell): if (neighbor not in map_close_list and neighbor not in frontier_open_list and neighbor not in frontier_close_list and is_valid_cell(neighbor, occupancy_grid)): queue_f.enqueue(neighbor) frontier_open_list.add(neighbor) if new_frontier: all_frontiers.append(new_frontier) # Continue outer BFS for neighbor in get_neighbors(cell): if (neighbor not in map_open_list and neighbor not in map_close_list and has_free_neighbor(neighbor, occupancy_grid)): queue_m.enqueue(neighbor) map_open_list.add(neighbor) return all_frontiers # Main call for the WFD autonomous exploration algorithm. def exploration(): while not rospy.is_shutdown(): current_map = get_occupancy_grid() robot_position = get_robot_position() # Calculate frontiers using WFD algorithm frontiers = WFD(current_map, robot_position) if not frontiers: rospy.loginfo("Exploration complete - no more frontiers") break # Calculate median points of each frontier cluster frontier_medians = [] for frontier in frontiers: median_point = calculate_median(frontier) frontier_medians.append(median_point) # Sort by distance to robot frontier_medians.sort(key=lambda point: distance(point, robot_position)) # Navigate to the closest frontier cluster for target in frontier_medians: if plan_path_to_point(target): move_to_point(target) # On arrival, perform complete sensor scan perform_scan() break save_map() Helper methods: Helper methods: def is_frontier(cell, occupancy_grid): """ Helper method to check if a cell is a frontier cell A frontier cell is an unknown cell with at least one free neighbor """ # Frontier has to be an unknown cell if occupancy_grid[cell] != UNKNOWN: return False # Check if at least one neighbor is free for neighbor in get_neighbors(cell): if occupancy_grid[neighbor] == FREE: return True return False def has_free_neighbor(cell, occupancy_grid): """ Helper method to check if a cell has at least one free neighbor This is a key optimization in WFD that, we only expand into known regions """ for neighbor in get_neighbors(cell): if occupancy_grid[neighbor] == FREE: return True return False def get_neighbors(cell): """Get the 4-connected [you can also do 8-connected] neighbors of a cell""" x, y = cell return [(x+1, y), (x-1, y), (x, y+1), (x, y-1)] def is_valid_cell(cell, occupancy_grid): """Helper method to check if a cell is within the grid boundaries""" x, y = cell height, width = len(occupancy_grid), len(occupancy_grid[0]) return 0 <= x < width and 0 <= y < height def is_frontier(cell, occupancy_grid): """ Helper method to check if a cell is a frontier cell A frontier cell is an unknown cell with at least one free neighbor """ # Frontier has to be an unknown cell if occupancy_grid[cell] != UNKNOWN: return False # Check if at least one neighbor is free for neighbor in get_neighbors(cell): if occupancy_grid[neighbor] == FREE: return True return False def has_free_neighbor(cell, occupancy_grid): """ Helper method to check if a cell has at least one free neighbor This is a key optimization in WFD that, we only expand into known regions """ for neighbor in get_neighbors(cell): if occupancy_grid[neighbor] == FREE: return True return False def get_neighbors(cell): """Get the 4-connected [you can also do 8-connected] neighbors of a cell""" x, y = cell return [(x+1, y), (x-1, y), (x, y+1), (x, y-1)] def is_valid_cell(cell, occupancy_grid): """Helper method to check if a cell is within the grid boundaries""" x, y = cell height, width = len(occupancy_grid), len(occupancy_grid[0]) return 0 <= x < width and 0 <= y < height One could further optimize this algorithm based on the specific robot’s configuration and use case w.r.t compute, time taken for exploration, the navigation path taken during exploration etc. As we see more real-world deployments of mobile robots (in warehouses, disaster zones, autonomous platforms, etc.), the need for this kind of self-directed navigation keeps growing. Frontier-based exploration remains one of the most reliable methods for autonomous mapping. It’s simple and effective: go to the edge of what you know, and look beyond. go to the edge of what you know, and look beyond. Hope this article was helpful in conveying the core principles behind autonomous robot exploration using frontier-based methods. References: References: [1] B. Yamauchi, “A frontier-based approach for autonomous exploration," Proceedings 1997 IEEE International Symposium on Computational Intelligence in Robotics and Automation CIRA'97. 'Towards New Computational Principles for Robotics and Automation', Monterey, CA, USA, 1997, pp. 146-151, doi: 10.1109/CIRA.1997.613851. keywords: {Mobile robots;Orbital robotics;Sonar navigation;Artificial intelligence;Laboratories;Testing;Humans;Indoor environments;Space exploration} [2] A. Topiwala, P. Inani, and A. Kathpal, “Frontier Based Exploration for Autonomous Robot,” arXiv preprint arXiv:1806.03581, 2018. [Online]. Available: https://arxiv.org/abs/1806.03581 https://arxiv.org/abs/1806.03581