lib/area_division.h
Go to the documentation of this file.
1 #ifndef AREA_DIVISION_LIB_H
2 #define AREA_DIVISION_LIB_H
3 
4 #include <vector>
5 #include <valarray>
6 #include <map>
7 #include <ros/ros.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <nav_msgs/OccupancyGrid.h>
11 
12 using namespace std;
13 using namespace ros;
14 
19 {
20 public:
24  area_division();
25 
29  void divide ();
30 
37  nav_msgs::OccupancyGrid get_grid (nav_msgs::OccupancyGrid map, string cps);
38 
43  void initialize_cps (map<string, vector<int>> cpss);
44 
51  void initialize_map (int r, int c, vector<signed char> src);
52 
53 private:
58  void assign (vector<valarray<double>> matrix);
59 
66  valarray<float> CalcConnectedMultiplier (valarray<float> dist1, valarray<float> dist2);
67 
75  valarray<double> FinalUpdateOnMetricMatrix (double CM, valarray<double> curentONe, valarray<float> CC);
76 
82  bool isThisAGoalState (int thres);
83 
88 
92  int rows;
93 
97  int cols;
98 
102  int nr;
103 
107  int ob;
108 
112  int max_iter;
113 
117  vector<signed char> gridmap;
118 
122  vector<vector<int>> cps;
123 
127  map<string, int> uuid_map;
128 
132  vector<valarray<int>> BWlist;
133 
137  valarray<int> A;
138 
142  vector<int> ArrayOfElements;
143 
147  vector<bool> regions;
148 
152  bool success;
153 
157  int discr;
158 };
159 
160 #endif // AREA_DIVISION_LIB_H
161 
valarray< int > A
Area assignment matrix.
map< string, int > uuid_map
UUID mapping of CPSs.
A class to divide the environment optimally among multiple cyber physical systems (CPSs)...
int max_iter
Maximum number of iterations of the optimization process.
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.
int rows
Number of rows in the grid map.
double variate_weight
Maximum variate weight of connected components.
vector< valarray< int > > BWlist
A binary array for each CPS which indicates free space.
vector< int > ArrayOfElements
Number of grid cells assigned to each CPS.
bool success
Whether the assignment succeeded.
int ob
Number of obstacles.
int cols
Number of columns in the grid map.
vector< signed char > gridmap
The environment grid map. Robots are represented by 2, obstacles by 1/-2, empty cells by -1...
int nr
Number of CPSs.


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