A class to divide the environment optimally among multiple cyber physical systems (CPSs).
More...
#include <area_division.h>
|
| void | assign (vector< valarray< double >> matrix) |
| | Define the assignment matrix based on a given distance metric matrix. More...
|
| |
| valarray< float > | CalcConnectedMultiplier (valarray< float > dist1, valarray< float > dist2) |
| | Calculate the connected multiplier. More...
|
| |
| valarray< double > | FinalUpdateOnMetricMatrix (double CM, valarray< double > curentONe, valarray< float > CC) |
| | Update the metric matrix. More...
|
| |
| bool | isThisAGoalState (int thres) |
| | Check if the areas assigned to each CPS are of similar size. More...
|
| |
|
| valarray< int > | A |
| | Area assignment matrix. More...
|
| |
| vector< int > | ArrayOfElements |
| | Number of grid cells assigned to each CPS. More...
|
| |
| vector< valarray< int > > | BWlist |
| | A binary array for each CPS which indicates free space. More...
|
| |
| int | cols |
| | Number of columns in the grid map. More...
|
| |
| vector< vector< int > > | cps |
| | Positions of the CPSs. More...
|
| |
| int | discr |
| | Maximum difference between number of assigned grid cells to each CPS. More...
|
| |
| vector< signed char > | gridmap |
| | The environment grid map. Robots are represented by 2, obstacles by 1/-2, empty cells by -1. More...
|
| |
| int | max_iter |
| | Maximum number of iterations of the optimization process. More...
|
| |
| int | nr |
| | Number of CPSs. More...
|
| |
| int | ob |
| | Number of obstacles. More...
|
| |
| vector< bool > | regions |
| | Whether the regions of the CPSs are connected. More...
|
| |
| int | rows |
| | Number of rows in the grid map. More...
|
| |
| bool | success |
| | Whether the assignment succeeded. More...
|
| |
| map< string, int > | uuid_map |
| | UUID mapping of CPSs. More...
|
| |
| double | variate_weight |
| | Maximum variate weight of connected components. More...
|
| |
A class to divide the environment optimally among multiple cyber physical systems (CPSs).
Definition at line 18 of file lib/area_division.h.
| area_division::area_division |
( |
| ) |
|
| void area_division::assign |
( |
vector< valarray< double >> |
matrix | ) |
|
|
private |
Define the assignment matrix based on a given distance metric matrix.
- Parameters
-
| matrix | A matrix of distance metrics. |
Definition at line 215 of file lib/area_division.cpp.
| valarray< float > area_division::CalcConnectedMultiplier |
( |
valarray< float > |
dist1, |
|
|
valarray< float > |
dist2 |
|
) |
| |
|
private |
Calculate the connected multiplier.
- Parameters
-
- Returns
- The connected multiplier array.
Definition at line 253 of file lib/area_division.cpp.
| void area_division::divide |
( |
| ) |
|
| valarray< double > area_division::FinalUpdateOnMetricMatrix |
( |
double |
CM, |
|
|
valarray< double > |
curentONe, |
|
|
valarray< float > |
CC |
|
) |
| |
|
private |
Update the metric matrix.
- Parameters
-
| CM | Correction multiplier. |
| curentONe | Current metric matrix. |
| CC | Connected multiplier array. |
- Returns
- The updated metric matrix.
Definition at line 275 of file lib/area_division.cpp.
| nav_msgs::OccupancyGrid area_division::get_grid |
( |
nav_msgs::OccupancyGrid |
map, |
|
|
string |
cps |
|
) |
| |
Get the region assigned to a CPS.
- Parameters
-
| map | Original grid map. |
| cps | UUID of the CPS. |
- Returns
- Grid map which contains obstacles in cells assigned to the CPS.
Definition at line 139 of file lib/area_division.cpp.
| void area_division::initialize_cps |
( |
map< string, vector< int >> |
cpss | ) |
|
Define the CPS positions.
- Parameters
-
| cpss | Mapping from UUIDs to positions of the CPSs. |
Definition at line 165 of file lib/area_division.cpp.
| void area_division::initialize_map |
( |
int |
r, |
|
|
int |
c, |
|
|
vector< signed char > |
src |
|
) |
| |
Define the grid map.
- Parameters
-
| r | Number of rows in the grid map. |
| c | Number of columns in the grid map. |
| src | Grid map describing the environment in the ROS format. |
Definition at line 199 of file lib/area_division.cpp.
| bool area_division::isThisAGoalState |
( |
int |
thres | ) |
|
|
private |
Check if the areas assigned to each CPS are of similar size.
- Parameters
-
| thres | The maximum number of grid cells that the areas assigned to different CPSs is allowed to differ. |
- Returns
- True, if the maximum assigned area to any CPS is at most thresh larger than the minimum assigned area to any CPS, false otherwise.
Definition at line 287 of file lib/area_division.cpp.
| valarray<int> area_division::A |
|
private |
| vector<int> area_division::ArrayOfElements |
|
private |
| vector<valarray<int> > area_division::BWlist |
|
private |
| vector<vector<int> > area_division::cps |
|
private |
Maximum difference between number of assigned grid cells to each CPS.
Definition at line 157 of file lib/area_division.h.
| vector<signed char> area_division::gridmap |
|
private |
The environment grid map. Robots are represented by 2, obstacles by 1/-2, empty cells by -1.
Definition at line 117 of file lib/area_division.h.
| int area_division::max_iter |
|
private |
| vector<bool> area_division::regions |
|
private |
| bool area_division::success |
|
private |
| map<string, int> area_division::uuid_map |
|
private |
| double area_division::variate_weight |
|
private |
The documentation for this class was generated from the following files: