===== T1e-expl - Mobile robot exploration: Frontier detection ======
The main task is to implement a frontier detector, which can be used to detect waypoints in autonomous spatial exploration.
|**Deadline** | November 2nd 2019 23:59 PST |
|**Points** | 3 |
|**Label in BRUTE** | t1e-expl |
|**Files to submit** | archive with ''ExplorationMap.py'' |
|**Resources** | {{ :courses:b4m36uir:hw:uir-t1e-expl.zip | T1e-expl package}}|
\\
===Assignment===
In ''ExplorationMap.py'' implement the function ''is_frontier'' to distinguish between frontier cells and non-frontiers cells.
def is_frontier(self, x, y):
"""
Method to determine whether a cell is a frontier.
Parameters
----------
x : int
discrete cell coordinate
y : int
discrete cell coordinate
----------
Returns
----------
boolean
True if the cell is a frontier, False otherwise
"""
# TODO t1e-expl
if (x + y) % 2 == 0:
return False
return True
\\
=== Approach ===
Frontiers are borders between free and unknown space, which may used to detect navigational goals to steer the robot towards the unknown environment, and thus to support mobile robot exploration. In grid maps, the cells that correspond to the frontiers are defined as follows
A **frontier cell** is a free cell which borders
- at least one other free cell
- at least one unknown cell
- no occupied cells.
Note, cells that border occupied cells are not considered frontiers in order to reduce false positives induced by the localization and mapping uncertainty.
The 8-neighborhood should be considered when implementing this task.
\\
=== Evaluation ===
The code can be evaluated using ''t1e-expl-eval.py''
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
import sys
from scipy import misc
import glob
import numpy as np
import os.path
from matplotlib import pyplot as plt
MAX_DISTANCE_TOLERANCE = 0
MAX_POINT_COUNT_DIFFERENCE = 0
INSTANCES = ['maps/map0','maps/map1','maps/map2']
sys.path.append('gridmap')
sys.path.append('exploration')
import GridMap as gmap
import ExplorationMap as emap
class Evaluator:
# loat trajectory as array of tuples
def load_map_image(self, filename):
ret = []
with open(filename, "r+") as f:
data = f.readlines() # read the text file
for line in data:
numArr = line.strip().split(" ") # numbers on a one line
if len(numArr) >1:
ret.append((int(numArr[0]),int(numArr[1])))
return ret
# compute point count difference
def point_count_diff(self, gt, est):
return abs( len(gt) -len(est) )
def dist_to_closest(self, gt, point):
minDist = 9999999.99
for x in range(len(gt)):
dist = np.sqrt( ((gt[x][0] - point[0])**2) + ((gt[x][1] - point[1])**2) )
if dist < minDist:
minDist = dist
if minDist is 0.0:
break
return minDist
# compute max distance between points of gt and estimate
def max_dist(self, gt, est):
maxDist = -100
for x in range(len(est)):
dist = self.dist_to_closest( gt, est[x] )
if dist > maxDist:
maxDist = dist
return maxDist
def eval_map(mappath):
imgpath = mappath + '_in.png'
gtpath = mappath + '_frontiers_gt.txt'
mapE = emap.ExplorationMap()
mapE.load_map_image( imgpath, 1)
evaluate = Evaluator()
est = mapE.list_frontiers()
gt = np.loadtxt(gtpath,delimiter=' ')
gt = [(gt[i,0],gt[i,1]) for i in range(gt.shape[0])]
# evaluate
if len(est) is 0:
print("Evaluation failed! -> no point were generated")
elif evaluate.point_count_diff( gt, est) > MAX_POINT_COUNT_DIFFERENCE:
print("Evaluation failed! -> point count difference is too high\n")
print("point count difference: %d" % evaluate.point_count_diff( gt, est) )
elif evaluate.max_dist( gt, est) > MAX_DISTANCE_TOLERANCE:
print("Evaluation failed! -> some points are too far from their correct locations\n")
print("max point difference: %f" % evaluate.max_dist( gt, est) )
else:
print("Evaluation success!")
emap.plot_frontiers(mapE)
plt.show()
if __name__=="__main__" :
for instance in INSTANCES:
eval_map( instance )
\\
=== Expected output ===
{{:courses:b4m36uir:hw:t1e-expl-map0.png?500|}}\\
{{:courses:b4m36uir:hw:t1e-expl-map1.png?500|}}\\
{{:courses:b4m36uir:hw:t1e-expl-map2.png?500|}}\\
\\
=== Appendix ===
\\
== Required dependencies ==
sudo apt install python-pip
pip install pillow
pip install scipy
\\
== FAQ and Known Issues ==
- The ''Gridmap.neighbors8'' and ''Gridmap.neighbors4'' functions filter our unpassable cells. Therefore, they cannot be directly used to check for obstacles in a cell's neighborhood.
- For some users ''scipy.misc.imread'' might be deprecated. If so, use ''imageio.imread'' instead. However, use ''scipy.misc.imread'' when uploading the task in BRUTE.
- The expected output refers to the provided testing script, which tests 3 input maps. However, the evaluation script in Brute tests 4 inputs in total.