minibatch.py
Go to the documentation of this file.
1 from __future__ import division
2 
3 import os
4 import time
5 import numpy as np
6 import cv2
7 
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
12 import rospy
13 from PIL import Image
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
19 def make_folder(location, folder_name):
20  if not os.path.exists(location + '/' + folder_name):
21  os.mkdir(location + '/' + folder_name)
22 
23 
24 def print_parameters(param_obj, path_obj):
25  file_parameter = open(path_obj.filepath + 'parameters.txt', 'w')
26  param = param_obj.__dict__
27  for par in param:
28  file_parameter.write(par + ": %s\n" % (getattr(param_obj, par)))
29 
30 
31 def final_routine(img_ini, param_obj, size, draw, extended_segments_th1_merged, ind, rooms_th1, filepath):
32  #post.clear_rooms(filepath + '8b_rooms_th1.png', param_obj, rooms_th1)
33  if draw.rooms_on_map:
34  segmentation_map_path = dsg.draw_rooms_on_map(img_ini, '8b_rooms_th1_on_map', size, filepath=filepath)
35  """
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)
38 
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),
41  size,
42  filepath=filepath)
43  """
44  # -------------------------------------POST-PROCESSING------------------------------------------------
45  #salva una nuova immagine in 8b_rooms_th1_on_map_post, con i colori spreaddati su tutta la mappa e restituisce
46  # l'array di colori presenti sulla mappa e il path della nuova mappa appena calcolata.
47  segmentation_map_path_post, colors = post.oversegmentation(segmentation_map_path, param_obj.th_post, filepath=filepath)
48  return segmentation_map_path_post, colors
49 
50 class Minibatch:
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']]
55 
56  start_time_main = time.time()
58  self.rooms_th1 = None
59  # ----------------------------1.0_LAYOUT OF ROOMS------------------------------------
60  # ------ starting layout
61  # read the image with removed non-structural components (obtained using rose)
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)
67 
68  # making a copy of original image of occupancy map
69  img_ini = originalImg.copy()
70 
71  # -------------------------------------------------------------------------------------
72 
73  # -----------------------------1.1_CANNY AND HOUGH-------------------------------------
74 
75  walls, canny = lay.start_canny_and_hough(img_rgb, param_obj)
76 
77  rospy.loginfo("[rose2] walls: {}".format(len(walls)))
78 
79  lines = walls
80  walls = lay.create_walls(lines)
81  rospy.loginfo("[rose2] lines: {} walls: {}".format(len(lines), len(walls)))
82 
83 
84  # ------------1.2_SET XMIN, YMIN, XMAX, YMAX OF walls-----------------------------------
85  # from all points of walls select x and y coordinates max and min.
86  extremes = sg.find_extremes(walls)
87  xmin = extremes[0]
88  xmax = extremes[1]
89  ymin = extremes[2]
90  ymax = extremes[3]
91  offset = param_obj.offset
92  xmin -= offset
93  xmax += offset
94  ymin -= offset
95  ymax += offset
96 
97  if xmin < 0:
98  xmin = 0
99  if ymin < 0:
100  ymin = 0
101  if xmax > size[0]:
102  xmax = size[0]
103  if ymax > size[1]:
104  ymax = size[1]
105 
106  # -------------------------------------------------------------------------------------
107 
108  # ---------------1.3 EXTERNAL CONTOUR--------------------------------------------------
109 
110  img_cont = originalImg.copy()
111  (contours, self.vertices) = lay.external_contour(img_cont)
112 
113 
114  # -------------------------------------------------------------------------------------
115 
116  # ---------------1.4_MEAN SHIFT TO FIND ANGULAR CLUSTERS-------------------------------
117 
118  indexes, walls, angular_clusters = lay.cluster_ang(param_obj.h, param_obj.minOffset, walls, diagonals=param_obj.diagonals)
119 
120  angular_clusters = lay.assign_orebro_direction(param_obj.comp, walls)
121 
122  # -------------------------------------------------------------------------------------
123 
124  # ---------------1.5_SPATIAL CLUSTERS--------------------------------------------------
125 
126  wall_clusters = lay.get_wall_clusters(walls, angular_clusters)
127 
128  wall_cluster_without_outliers = []
129  for cluster in wall_clusters:
130  if cluster != -1:
131  wall_cluster_without_outliers.append(cluster)
132 
133  # now that I have a list of clusters related to walls, I want to merge those very close each other
134  # obtain representatives of clusters (all except outliers)
135  representatives_segments = lay.get_representatives(walls, wall_cluster_without_outliers)
136 
137  representatives_segments = sg.spatial_clustering(param_obj.spatialClusteringLineSegmentsThreshold, representatives_segments)
138 
139  # now we have a set of Segments with correct spatial cluster, now set the others with same wall_cluster
140  spatial_clusters = lay.new_spatial_cluster(walls, representatives_segments, param_obj)
141 
142  # -------------------------------------------------------------------------------------
143 
144  # ------------------------1.6 EXTENDED_LINES-------------------------------------------
145 
146  (self.extended_lines, self.extended_segments) = lay.extend_line(spatial_clusters, walls, xmin, xmax, ymin, ymax)
147 
148 
149  self.extended_segments = sg.set_weights(self.extended_segments, walls)
150  # this is used to merge together the extended_segments that are very close each other.
151  extended_segments_merged = ExtendedSegment.merge_together(self.extended_segments, param_obj.distance_extended_segment, walls)
152  extended_segments_merged = sg.set_weights(extended_segments_merged, walls)
153  # this is needed in order to maintain the extended lines of the offset STANDARD
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)
156  lis = []
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)
161 
162  lis = sg.set_weights(lis, walls)
163  lis, _ = sg.remove_less_representatives(lis, 0.1)
164  for el in lis:
165  self.extended_segments_th1_merged.append(el)
166  #threshold lines (added)
167  for e in self.extended_segments_th1_merged:
168  if(e.weight < param_obj.th1):
169  self.extended_segments_th1_merged.remove(e)
170 
171  # -------------------------------------------------------------------------------------
172 
173  # --------------------------------1.7_EDGES--------------------------------------------
174 
175  # creating edges as intersection between extended lines
176 
177  edges = sg.create_edges(self.extended_segments)
178  self.edges_th1 = sg.create_edges(self.extended_segments_th1_merged)
179  # sg.set_weight_offset_edges(border_lines, edges_th1)
180 
181  # -------------------------------------------------------------------------------------
182 
183  # ---------------------------1.8_SET EDGES WEIGHTS-------------------------------------
184 
185  edges = sg.set_weights(edges, walls)
186  self.edges_th1 = sg.set_weights(self.edges_th1, walls)
187  # threshold edges (added)
188  for e in self.edges_th1:
189  if (e.weight < param_obj.threshold_edges):
190  self.edges_th1.remove(e)
191  # -------------------------------------------------------------------------------------
192 
193  # ----------------------------1.9_CREATE CELLS-----------------------------------------
194  cells_th1 = Surface.create_cells(self.edges_th1)
195 
196 
197  # -------------------------------------------------------------------------------------
198 
199  # ----------------Classification of Facces CELLE-----------------------------------------------------
200  if self.vertices is None:
201  rospy.loginfo('[rose2] ROOMS NOT FOUND')
202  else:
203  # Identification of Cells/Faces that are Inside or Outside the map
204  global centroid
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')
210  return
211  # -------------------------------------------------------------------------------------
212 
213  # ---------------------------POLYGON CELLS---------------------------------------------
214  # TODO this method could be deleted. check. Not used anymore.
215  (cells_polygons_th1, polygon_out_th1, polygon_partial_th1, centroid_th1) = lay.create_polygon(cells_th1, cells_out_th1,cells_partials_th1)
216 
217 
218  # ----------------------MATRICES L, D, D^-1, ED M = D^-1 * L--------------------------
219 
220  (matrix_l_th1, matrix_d_th1, matrix_d_inv_th1, X_th1) = lay.create_matrices(cells_th1, sigma=param_obj.sigma)
221 
222  # -------------------------------------------------------------------------------------
223 
224  # ----------------DBSCAN PER TROVARE CELLE NELLA STESSA STANZA-------------------------
225 
226  cluster_cells_th1 = lay.DB_scan(param_obj.eps, param_obj.minPts, X_th1, cells_polygons_th1)
227  #needed for dsg.draw_rooms
228  if rooms_voronoi:
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)
233 
234  # -------------------------------------------------------------------------------------
235 
236  # ----------------------------POLYGON ROOMS--------------------------------------------
237 
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)))
240  # -------------------------------------------------------------------------------------
241 
242  # searching partial cells
243  border_coordinates = [xmin, ymin, xmax, ymax]
244  # TODO check how many time is computed
245 
246  cells_partials_th1, polygon_partial_th1 = lay.get_partial_cells(cells_th1, cells_out_th1, border_coordinates)
247 
248  polygon_out_th1 = lay.get_out_polygons(cells_out_th1)
249  #apply voronoi method to find more rooms (it's slower)
250  if rooms_voronoi:
251  fig, ax, patches = dsg.draw_rooms(self.rooms_th1, colors_th1, '8b_rooms_th1', size, filepath=filepath)
252  # ---------------------------------END LAYOUT------------------------------------------
253  ind = 0
254  segmentation_map_path_post, colors = final_routine(img_ini, param_obj, size, draw,self.extended_segments_th1_merged, ind,
255  self.rooms_th1,
256  filepath=filepath)
257  old_colors = []
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:
261  ind += 1
262  old_colors = colors
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,
267  filepath=filepath)
268  self.rooms_th1 = make_rooms(patches)
269  colors_th1 = []
270  for r in self.rooms_th1:
271  colors_th1.append(0)
272  rospy.loginfo("[rose2] Number of rooms found after voronoi method: {}".format(len(patches)))
273  #dsg.draw_rooms(self.rooms_th1, colors_th1, '8b_rooms_th1', size, filepath=filepath)
274 
275 def make_rooms(patches):
276  l = []
277  for p in patches:
278  l.append(Polygon(p.get_path().vertices))
279  return l
Surface.create_cells
def create_cells(edges)
Definition: Surface.py:24
minibatch.Minibatch.edges_th1
edges_th1
Definition: minibatch.py:178
minibatch.Minibatch.extended_segments
extended_segments
Definition: minibatch.py:149
minibatch.Minibatch.rooms_th1
rooms_th1
Definition: minibatch.py:58
parameters.ParameterDraw
Definition: parameters.py:105
minibatch.make_folder
def make_folder(location, folder_name)
Definition: minibatch.py:19
minibatch.Minibatch.start_main
def start_main(self, par, param_obj, cleanImg, originalImg, filepath, rooms_voronoi)
Definition: minibatch.py:51
minibatch.final_routine
def final_routine(img_ini, param_obj, size, draw, extended_segments_th1_merged, ind, rooms_th1, filepath)
Definition: minibatch.py:31
minibatch.Minibatch
Definition: minibatch.py:50
ExtendedSegment.merge_together
def merge_together(extended_segments, distance, walls)
Definition: ExtendedSegment.py:227
minibatch.make_rooms
def make_rooms(patches)
Definition: minibatch.py:275
minibatch.print_parameters
def print_parameters(param_obj, path_obj)
Definition: minibatch.py:24


rose2
Author(s): Gabriele Somaschini, Matteo Luperto
autogenerated on Wed Jun 28 2023 02:21:53