Search
In the mobile-robot exploration, the robot has to select its goals. This goal selection rely on identification of information-rich regions of interest. A simple approach is to use free-edges (border between the free and unknown parts of the map) for exploration. The main task is to implement a function that will find the free-edge cells and cluster them to obtain list of free-edge representatives from which goals for exploration are further selected.
HexapodExplorer.py
In class HexapodExplorer.py implement the find_free_edge_frontiers function. The purpose of the function is to find the free-edge frontiers which are centroids of cells on the border between the free and unknown cells. A free-edge cell is a free cell which borders:
find_free_edge_frontiers
Free-edges are sets of free-edge cells connected into the connected component (8-neighborhood, a.k.a. 2 jump connected component, is considered). Free-edge frontiers are centroids of the segmented free-edges.
The input parameters of the function is:
grid_map
The function returns:
None
The find_free_edge_frontiers function in the HexapodExplorer.py class has a following prescription:
def find_free_edge_frontiers(self, grid_map): """Method to find the free-edge frontiers (edge clusters between the free and unknown areas) Args: grid_map: OccupancyGrid - gridmap of the environment Returns: pose_list: Pose[] - list of selected frontiers """
There are man different ways on how to accomplish the given task. The recommended approach for the detection of free edge frontiers consist of three steps:
The detailed description of the individual steps follows.
First, the detection of the free-edge cells is performed. The free-edge cell $m_i$ is characterized by the following properties given the occupancy grid map:
An efficient approach to free-cell detection is using the 2D convolution with subsequent thresholding. The task is to find a proper 2D convolution mask to distinguish between the different constitutions of the cell 8-neighborhood consisting of free, unknown, and occupied cells.Hint You should draw the bounding examples of 8-neighborhood and think about the 2D-convolution as of a weighted sum of this neighborhood.
The 2D convolution itself can be done easily using the scipy.ndimage library using the following code:
scipy.ndimage
import scipy.ndimage as ndimg data_c = ndimg.convolve(data, mask, mode='constant', cval=0.0)
1
0
Figure (click to view)
From left to right:
The second step is to perform the connected component analysis on the free-edge cells. A nice explanatory overview of the connected component analysis can be found here. The main idea is to connect the free-edge cells that coincide into the connected component to effectively reduce the number of frontiers and select only the representatives of the whole cluster.
For the connectivity analysis you can use the following code:
import skimage.measure as skm labeled_image, num_labels = skm.label(free_cells, connectivity=2, return_num=True)
An example of correctly connected free-edge clusters is visualized in following figure together with free-edge centroids marked by red points.
Finally, it is necessary to obtain the cluster centroids as the mean of $x, y$ coordinates of connected free-edge.
The code can be evaluated using the following script (also attached as t1e-expl.py).
t1e-expl.py
#!/usr/bin/env python3 # -*- coding: utf-8 -*- import matplotlib.pyplot as plt import sys import os import math import numpy as np sys.path.append('hexapod_robot') sys.path.append('hexapod_explorer') #import hexapod robot and explorer import HexapodRobot as hexapod import HexapodExplorer as explorer #import communication messages from messages import * #pickle import pickle if __name__=="__main__": explor = explorer.HexapodExplorer() dataset = pickle.load( open( "frontier_detection.bag", "rb" ) ) for gridmap in dataset: #find free edges points = explor.find_free_edge_frontiers(gridmap) #plot the map fig, ax = plt.subplots() #plot the gridmap gridmap.plot(ax) #plot the cluster centers if points is not None: for p in points: plt.plot([p.position.x],[p.position.y],'.', markersize=20) plt.xlabel('x[m]') plt.ylabel('y[m]') ax.set_aspect('equal', 'box') plt.show()