1 from __future__
import division
8 import util.layout
as lay
9 import util.postprocessing
as post
10 from object
import Segment
as sg, ExtendedSegment
11 from object
import Surface
as Surface
14 import rose_v2_repo.parameters
as parameters
15 import util.disegna
as dsg
16 import util.voronoi
as vr
17 from shapely.geometry.polygon
import Polygon
18 from matplotlib
import pyplot
as plt
20 if not os.path.exists(location +
'/' + folder_name):
21 os.mkdir(location +
'/' + folder_name)
25 file_parameter = open(path_obj.filepath +
'parameters.txt',
'w')
26 param = param_obj.__dict__
28 file_parameter.write(par +
": %s\n" % (getattr(param_obj, par)))
31 def final_routine(img_ini, param_obj, size, draw, extended_segments_th1_merged, ind, rooms_th1, filepath):
34 segmentation_map_path = dsg.draw_rooms_on_map(img_ini,
'8b_rooms_th1_on_map', size, filepath=filepath)
36 if draw.rooms_on_map_prediction:
37 dsg.draw_rooms_on_map_prediction(img_ini, '8b_rooms_th1_on_map_prediction', size, filepath=filepath)
39 if draw.rooms_on_map_lines:
40 dsg.draw_rooms_on_map_plus_lines(img_ini, extended_segments_th1_merged, '8b_rooms_th1_on_map_th1' + str(ind),
47 segmentation_map_path_post, colors = post.oversegmentation(segmentation_map_path, param_obj.th_post, filepath=filepath)
48 return segmentation_map_path_post, colors
51 def start_main(self, par, param_obj, cleanImg, originalImg, filepath, rooms_voronoi):
52 param_obj.tab_comparison = [[
''], [
'precision_micro'], [
'precision_macro'], [
'recall_micro'], [
'recall_macro'],
53 [
'iou_micro_mean_seg_to_gt'], [
'iou_macro_seg_to_gt'], [
'iou_micro_mean_gt_to_seg'],
54 [
'iou_macro_gt_to_seg']]
56 start_time_main = time.time()
62 orebro_img = cleanImg.copy()
63 width = orebro_img.shape[1]
64 height = orebro_img.shape[0]
65 size = [width, height]
66 img_rgb = cv2.bitwise_not(orebro_img)
69 img_ini = originalImg.copy()
75 walls, canny = lay.start_canny_and_hough(img_rgb, param_obj)
77 rospy.loginfo(
"[rose2] walls: {}".format(len(walls)))
80 walls = lay.create_walls(lines)
81 rospy.loginfo(
"[rose2] lines: {} walls: {}".format(len(lines), len(walls)))
86 extremes = sg.find_extremes(walls)
91 offset = param_obj.offset
110 img_cont = originalImg.copy()
111 (contours, self.vertices) = lay.external_contour(img_cont)
118 indexes, walls, angular_clusters = lay.cluster_ang(param_obj.h, param_obj.minOffset, walls, diagonals=param_obj.diagonals)
120 angular_clusters = lay.assign_orebro_direction(param_obj.comp, walls)
126 wall_clusters = lay.get_wall_clusters(walls, angular_clusters)
128 wall_cluster_without_outliers = []
129 for cluster
in wall_clusters:
131 wall_cluster_without_outliers.append(cluster)
135 representatives_segments = lay.get_representatives(walls, wall_cluster_without_outliers)
137 representatives_segments = sg.spatial_clustering(param_obj.spatialClusteringLineSegmentsThreshold, representatives_segments)
140 spatial_clusters = lay.new_spatial_cluster(walls, representatives_segments, param_obj)
146 (self.extended_lines, self.
extended_segments) = lay.extend_line(spatial_clusters, walls, xmin, xmax, ymin, ymax)
152 extended_segments_merged = sg.set_weights(extended_segments_merged, walls)
154 border_lines = lay.set_weight_offset(extended_segments_merged, xmax, xmin, ymax, ymin)
155 self.extended_segments_th1_merged, ex_li_removed = sg.remove_less_representatives(extended_segments_merged, param_obj.th1)
157 for line
in ex_li_removed:
158 short_line = sg.create_short_ex_lines(line, walls, size, self.extended_segments_th1_merged)
159 if short_line
is not None:
160 lis.append(short_line)
162 lis = sg.set_weights(lis, walls)
163 lis, _ = sg.remove_less_representatives(lis, 0.1)
165 self.extended_segments_th1_merged.append(el)
167 for e
in self.extended_segments_th1_merged:
168 if(e.weight < param_obj.th1):
169 self.extended_segments_th1_merged.remove(e)
178 self.
edges_th1 = sg.create_edges(self.extended_segments_th1_merged)
185 edges = sg.set_weights(edges, walls)
189 if (e.weight < param_obj.threshold_edges):
200 if self.vertices
is None:
201 rospy.loginfo(
'[rose2] ROOMS NOT FOUND')
205 if par.metodo_classificazione_celle == 1:
206 rospy.loginfo(
"[rose2] 1.classification method: {}".format(par.metodo_classificazione_celle))
207 (cells_th1, cells_out_th1, cells_polygons_th1, indexes_th1, cells_partials_th1, contour_th1, centroid_th1, points_th1) = lay.classification_surface(self.vertices, cells_th1, param_obj.division_threshold)
208 if len(cells_th1) == 0:
209 rospy.loginfo(
'[rose2] ROOMS NOT FOUND')
215 (cells_polygons_th1, polygon_out_th1, polygon_partial_th1, centroid_th1) = lay.create_polygon(cells_th1, cells_out_th1,cells_partials_th1)
220 (matrix_l_th1, matrix_d_th1, matrix_d_inv_th1, X_th1) = lay.create_matrices(cells_th1, sigma=param_obj.sigma)
226 cluster_cells_th1 = lay.DB_scan(param_obj.eps, param_obj.minPts, X_th1, cells_polygons_th1)
229 metric_map_path = filepath +
'originalMap.png'
230 plt.imsave(metric_map_path, originalImg, cmap=
'gray')
231 colors_th1, fig, ax = dsg.draw_dbscan(cluster_cells_th1, cells_th1, cells_polygons_th1, self.
edges_th1,
232 contours,
'7b_DBSCAN_th1', size, filepath=filepath)
238 self.
rooms_th1, spaces_th1 = lay.create_space(cluster_cells_th1, cells_th1, cells_polygons_th1)
239 rospy.loginfo(
"[rose2] Number of rooms found: {}".format(len(self.
rooms_th1)))
243 border_coordinates = [xmin, ymin, xmax, ymax]
246 cells_partials_th1, polygon_partial_th1 = lay.get_partial_cells(cells_th1, cells_out_th1, border_coordinates)
248 polygon_out_th1 = lay.get_out_polygons(cells_out_th1)
251 fig, ax, patches = dsg.draw_rooms(self.
rooms_th1, colors_th1,
'8b_rooms_th1', size, filepath=filepath)
254 segmentation_map_path_post, colors =
final_routine(img_ini, param_obj, size, draw,self.extended_segments_th1_merged, ind,
258 voronoi_graph, coordinates = vr.compute_voronoi_graph(metric_map_path, param_obj,
259 False,
'', param_obj.bormann, filepath=filepath)
260 while old_colors != colors
and ind < param_obj.iterations:
263 vr.voronoi_segmentation(patches, colors_th1, size, voronoi_graph, coordinates, param_obj.comp,
264 metric_map_path, ind, filepath=filepath)
265 segmentation_map_path_post, colors =
final_routine(img_ini, param_obj, size, draw,
266 self.extended_segments_th1_merged, ind, self.
rooms_th1,
272 rospy.loginfo(
"[rose2] Number of rooms found after voronoi method: {}".format(len(patches)))
278 l.append(Polygon(p.get_path().vertices))