lib/area_division.cpp
Go to the documentation of this file.
1 #include "lib/area_division.h"
2 
4 {
5  // read parameters
6  NodeHandle nh;
7  nh.param(this_node::getName() + "/optimizer/iterations", max_iter, 10);
8  nh.param(this_node::getName() + "/optimizer/variate_weight", variate_weight, 0.01);
9  nh.param(this_node::getName() + "/optimizer/discrepancy", discr, 30);
10 }
11 
13 {
14  // initializations
15  int NoTiles = rows*cols;
16  double fairDivision = 1.0 / nr;
17  int effectiveSize = NoTiles - nr - ob;
18  int termThr;
19  if (effectiveSize % nr !=0) {
20  termThr=1;
21  }
22  else {
23  termThr=0;
24  }
25  ROS_DEBUG("%d free cells.", effectiveSize);
26 
27  // initialize distances of cells to cps
28  vector<valarray<double>> AllDistances(nr, valarray<double>(rows*cols));
29  for (int i=0; i<rows; i++) {
30  for (int j=0; j<cols;j++) {
31  for (int r=0; r<nr; r++) {
32  AllDistances[r][i*cols+j] = hypot(cps[r][1]-i, cps[r][0]-j);
33  }
34  }
35  }
36  ROS_DEBUG("Computed distances from CPSs to all cells.");
37 
38 
39  vector<valarray<double>> MetricMatrix = AllDistances;
40 
41  // perform area division
42  success = false;
43  while (termThr<=discr && !success) {
44  ROS_DEBUG("Try division with discrepancy %d<=%d.", termThr, discr);
45 
46  // initializations
47  double downThres = ((double)NoTiles-(double)termThr*(nr-1)) / (double)(NoTiles*nr);
48  double upperThres = ((double)NoTiles+termThr) / (double)(NoTiles*nr);
49  success = true;
50 
51  // main optimization loop
52  int iter = 0;
53  while (iter <= max_iter) {
54  assign(MetricMatrix);
55 
56  // find connected areas
57  vector<valarray<float>> ConnectedMultiplierList(nr);
58  double plainErrors[nr];
59  double divFairError[nr];
60  for (int r=0; r<nr; r++) {
61  valarray<float> ConnectedMultiplier(1, rows*cols);
62  regions[r] = true;
63 
64  connected_components cc(BWlist[r], rows, cols, true);
65  valarray<int> Ilabel = cc.compactLabeling();
66  // at least one unconnected regions among r-robot's regions is found
67  if (cc.getMaxLabel() > 1) {
68  regions[r] = false;
69 
70  // find robot's sub-region and construct robot and non-robot binary regions
71  cc.constructBinaryImages(Ilabel[cps[r][1] * cols + cps[r][0]]);
72 
73  // construct the final connected component multiplier
75  }
76  ConnectedMultiplierList[r] = ConnectedMultiplier;
77 
78  // calculate the deviation from the the optimal assignment
79  plainErrors[r] = ArrayOfElements[r] / (double) effectiveSize;
80  if (plainErrors[r] < downThres) {
81  divFairError[r] = downThres - plainErrors[r];
82  }
83  else if (plainErrors[r] > upperThres) {
84  divFairError[r] = upperThres - plainErrors[r];
85  }
86  }
87 
88  // exit conditions
89  if (isThisAGoalState(termThr)) {
90  break;
91  }
92 
93  // check fairness among different partitions
94  double TotalNegPerc = 0.0, totalNegPlainErrors = 0.0;
95  double correctionMult[nr];
96  for (int r=0; r<nr; r++) {
97  if (divFairError[r] < 0) {
98  TotalNegPerc += abs(divFairError[r]);
99  totalNegPlainErrors += plainErrors[r];
100  }
101  correctionMult[r] = 1.0;
102  }
103 
104  // restore fairness
105  for (int r=0; r<nr; r++) {
106  if (totalNegPlainErrors != 0.0) {
107  if (divFairError[r]<0.0) {
108  correctionMult[r] = 1.0 + (plainErrors[r] / totalNegPlainErrors) * (TotalNegPerc / 2.0);
109  }
110  else {
111  correctionMult[r] = 1.0 - (plainErrors[r] / totalNegPlainErrors) * (TotalNegPerc / 2.0);
112  }
113  }
114  MetricMatrix[r] = FinalUpdateOnMetricMatrix(correctionMult[r], MetricMatrix[r], ConnectedMultiplierList[r]);
115  }
116 
117  iter++;
118  }
119 
120  // could not find area division
121  if (iter >= max_iter) {
122  max_iter = max_iter/2;
123  success = false;
124 
125  ROS_DEBUG("Failed to divide in %d iterations.", iter);
126 
127  // increase allowed area discrepancy
128  termThr++;
129  }
130 
131  else
132  ROS_DEBUG("Succeeded division with discrepancy %d after %d < %d iterations", termThr, iter, max_iter);
133  }
134 
135  if (success == false)
136  ROS_ERROR("Area division failed!");
137 }
138 
139 nav_msgs::OccupancyGrid area_division::get_grid (nav_msgs::OccupancyGrid map, string cps)
140 {
141  // create new grid map
142  nav_msgs::OccupancyGrid assigned;
143  assigned = map;
144 
145  for (int i=0; i<rows; i++) {
146  for (int j=0; j<cols;j++) {
147  // mark assigned cells as free
148  if (A[i*cols+j] == uuid_map[cps]) {
149  assigned.data[i*cols+j] = 0;
150  }
151 
152  // mark cells assigned to other cpss as obstacles
153  else {
154  assigned.data[i*cols+j] = 100;
155  }
156  }
157  }
158 
159  assigned.header.stamp = Time::now();
160  assigned.info.map_load_time == Time::now();
161 
162  return assigned;
163 }
164 
165 void area_division::initialize_cps (map<string, vector<int>> cpss)
166 {
167  // initialize
168  nr = 0;
169  cps.clear();
170  uuid_map.clear();
171  A.resize(rows*cols);
172  regions.clear();
173  regions.resize(cpss.size());
174 
175  // place cpss in the map
176  for (auto c : cpss) {
177  // divison algorithm assumes origin at top left
178  int x = c.second[0];
179  int y = c.second[1];
180 
181  // index of position in grid map
182  int idx = y * cols + x;
183 
184  ROS_DEBUG("CPS %d (%s) at (%d,%d) index %d", nr, c.first.c_str(), x, y, idx);
185 
186  // place cps in data structures
187  gridmap[idx] = numeric_limits<signed char>::max();
188  A[idx] = nr;
189 
190  // store cps position and mapping of uuid
191  cps.push_back(initializer_list<int>{x,y});
192  uuid_map[c.first] = nr;
193 
194  // count number of cpss
195  nr++;
196  }
197 }
198 
199 void area_division::initialize_map (int r, int c, vector<signed char> src)
200 {
201  // initialization
202  rows = r;
203  cols = c;
204  gridmap = src;
205  ob = 0;
206 
207  // count number of occupied cells
208  for (int i=0; i<gridmap.size(); ++i)
209  if (gridmap[i] >= 50)
210  ++ob;
211 
212  ROS_DEBUG("There are %d occupied cells.", ob);
213 }
214 
215 void area_division::assign (vector<valarray<double>> matrix)
216 {
217  BWlist.resize(nr);
218  for (int r=0; r<nr; r++) {
219  BWlist[r].resize(rows*cols);
220  BWlist[r][cps[r][1] * cols + cps[r][0]] = 1;
221  }
222 
223  ArrayOfElements.clear();
224  ArrayOfElements.resize(nr);
225  for (int i=0; i<rows; i++) {
226  for (int j=0; j<cols; j++) {
227  // free grid cell, assign to a robot
228  if (gridmap[i*cols+j] < 50) {
229  // find index of robot that has lowest metric value
230  double minV = matrix[0][i*cols+j];
231  int indMin = 0;
232  for (int r=1; r<nr; r++) {
233  if (matrix[r][i*cols+j] <= minV) {
234  minV = matrix[r][i*cols+j];
235  indMin = r;
236  }
237  }
238 
239  // store assignment
240  A[i*cols+j] = indMin;
241  BWlist[indMin][i*cols+j] = 1;
242  ArrayOfElements[indMin]++;
243  }
244 
245  // obstacle
246  else if (gridmap[i*cols+j] < numeric_limits<signed char>::max()) {
247  A[i*cols+j] = nr;
248  }
249  }
250  }
251 }
252 
253 valarray<float> area_division::CalcConnectedMultiplier(valarray<float> dist1, valarray<float> dist2)
254 {
255  valarray<float> returnM(rows*cols);
256  float MaxV = 0;
257  float MinV = numeric_limits<float>::max();
258  for (int i=0;i<rows;i++){
259  for (int j=0;j<cols;j++){
260  returnM[i*cols+j] = dist1[i*cols+j] - dist2[i*cols+j];
261  if (MaxV < returnM[i*cols+j]) {MaxV = returnM[i*cols+j];}
262  if (MinV > returnM[i*cols+j]) {MinV = returnM[i*cols+j];}
263  }
264  }
265 
266  for (int i=0;i<rows;i++){
267  for (int j=0;j<cols;j++){
268  returnM[i*cols+j] =(returnM[i*cols+j] - MinV)*((2*(float)variate_weight)/(MaxV-MinV))+(1-(float)variate_weight);
269  }
270  }
271 
272  return returnM;
273 }
274 
275 valarray<double> area_division::FinalUpdateOnMetricMatrix(double CM, valarray<double> curentONe, valarray<float> CC)
276 {
277  valarray<double> MMnew(rows*cols);
278 
279  for (int i=0; i<MMnew.size(); ++i) {
280  MMnew[i] = curentONe[i] * CM * CC[i];
281  }
282 
283  return MMnew;
284 }
285 
286 
288 {
289  int maxCellsAss = 0;
290  int minCellsAss = numeric_limits<int>::max();
291 
292 
293  for (int r=0; r<nr; r++) {
294  if (maxCellsAss < ArrayOfElements[r]) {
295  maxCellsAss = ArrayOfElements[r];
296  }
297  if (minCellsAss > ArrayOfElements[r]) {
298  minCellsAss = ArrayOfElements[r];
299  }
300 
301  if (!regions[r]) {
302  return false;
303  }
304  }
305 
306  return (maxCellsAss - minCellsAss) <= thres;
307 }
valarray< int > A
Area assignment matrix.
map< string, int > uuid_map
UUID mapping of CPSs.
void assign(vector< valarray< double >> matrix)
Define the assignment matrix based on a given distance metric matrix.
int getMaxLabel()
Get the max label of the labeling process which is in the range [0,max_label].
int max_iter
Maximum number of iterations of the optimization process.
void constructBinaryImages(int robotsLabel)
Create binary arrays of connected labels.
vector< bool > regions
Whether the regions of the CPSs are connected.
vector< vector< int > > cps
Positions of the CPSs.
int discr
Maximum difference between number of assigned grid cells to each CPS.
bool isThisAGoalState(int thres)
Check if the areas assigned to each CPS are of similar size.
Use row-by-row labeling algorithm to label connected components. The algorithm makes two passes over ...
int rows
Number of rows in the grid map.
double variate_weight
Maximum variate weight of connected components.
valarray< float > NormalizedEuclideanDistanceBinary(bool RobotR)
Calculate the normalized euclidean distance transform of a binary image with foreground pixels set to...
void initialize_cps(map< string, vector< int >> cpss)
Define the CPS positions.
void divide()
Perform the area division.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
valarray< int > compactLabeling()
Rearrange the labels to make the label numbers consecutive.
vector< valarray< int > > BWlist
A binary array for each CPS which indicates free space.
void initialize_map(int r, int c, vector< signed char > src)
Define the grid map.
vector< int > ArrayOfElements
Number of grid cells assigned to each CPS.
bool success
Whether the assignment succeeded.
area_division()
Constructor.
int ob
Number of obstacles.
valarray< double > FinalUpdateOnMetricMatrix(double CM, valarray< double > curentONe, valarray< float > CC)
Update the metric matrix.
int cols
Number of columns in the grid map.
nav_msgs::OccupancyGrid get_grid(nav_msgs::OccupancyGrid map, string cps)
Get the region assigned to a CPS.
vector< signed char > gridmap
The environment grid map. Robots are represented by 2, obstacles by 1/-2, empty cells by -1...
valarray< float > CalcConnectedMultiplier(valarray< float > dist1, valarray< float > dist2)
Calculate the connected multiplier.
#define ROS_ERROR(...)
int nr
Number of CPSs.
#define ROS_DEBUG(...)


area_division
Author(s): Micha Sende
autogenerated on Tue Jan 19 2021 03:30:02