7 nh.
param(this_node::getName() +
"/optimizer/iterations",
max_iter, 10);
9 nh.
param(this_node::getName() +
"/optimizer/discrepancy",
discr, 30);
16 double fairDivision = 1.0 /
nr;
17 int effectiveSize = NoTiles -
nr -
ob;
19 if (effectiveSize %
nr !=0) {
25 ROS_DEBUG(
"%d free cells.", effectiveSize);
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);
36 ROS_DEBUG(
"Computed distances from CPSs to all cells.");
39 vector<valarray<double>> MetricMatrix = AllDistances;
44 ROS_DEBUG(
"Try division with discrepancy %d<=%d.", termThr,
discr);
47 double downThres = ((double)NoTiles-(
double)termThr*(
nr-1)) / (double)(NoTiles*
nr);
48 double upperThres = ((double)NoTiles+termThr) / (double)(NoTiles*nr);
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);
76 ConnectedMultiplierList[r] = ConnectedMultiplier;
80 if (plainErrors[r] < downThres) {
81 divFairError[r] = downThres - plainErrors[r];
83 else if (plainErrors[r] > upperThres) {
84 divFairError[r] = upperThres - plainErrors[r];
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];
101 correctionMult[r] = 1.0;
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);
111 correctionMult[r] = 1.0 - (plainErrors[r] / totalNegPlainErrors) * (TotalNegPerc / 2.0);
125 ROS_DEBUG(
"Failed to divide in %d iterations.", iter);
132 ROS_DEBUG(
"Succeeded division with discrepancy %d after %d < %d iterations", termThr, iter,
max_iter);
142 nav_msgs::OccupancyGrid assigned;
145 for (
int i=0; i<
rows; i++) {
146 for (
int j=0; j<
cols;j++) {
149 assigned.data[i*cols+j] = 0;
154 assigned.data[i*cols+j] = 100;
159 assigned.header.stamp = Time::now();
160 assigned.info.map_load_time == Time::now();
176 for (
auto c : cpss) {
182 int idx = y * cols + x;
184 ROS_DEBUG(
"CPS %d (%s) at (%d,%d) index %d",
nr, c.first.c_str(), x, y, idx);
187 gridmap[idx] = numeric_limits<signed char>::max();
191 cps.push_back(initializer_list<int>{x,y});
208 for (
int i=0; i<
gridmap.size(); ++i)
218 for (
int r=0; r<
nr; r++) {
225 for (
int i=0; i<
rows; i++) {
226 for (
int j=0; j<
cols; j++) {
230 double minV = matrix[0][i*cols+j];
232 for (
int r=1; r<
nr; r++) {
233 if (matrix[r][i*cols+j] <= minV) {
234 minV = matrix[r][i*cols+j];
240 A[i*cols+j] = indMin;
241 BWlist[indMin][i*cols+j] = 1;
246 else if (
gridmap[i*cols+j] < numeric_limits<signed char>::max()) {
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];}
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);
279 for (
int i=0; i<MMnew.size(); ++i) {
280 MMnew[i] = curentONe[i] * CM * CC[i];
290 int minCellsAss = numeric_limits<int>::max();
293 for (
int r=0; r<
nr; r++) {
306 return (maxCellsAss - minCellsAss) <= thres;
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 ¶m_name, T ¶m_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.