area_division.h
Go to the documentation of this file.
1 #ifndef AREA_DIVISION_H
2 #define AREA_DIVISION_H
3 
4 #include <ros/ros.h>
5 #include <map>
6 #include <vector>
7 #include <geometry_msgs/Pose.h>
8 #include <geometry_msgs/PoseStamped.h>
9 #include <geometry_msgs/Vector3.h>
10 #include <nav_msgs/OccupancyGrid.h>
11 #include <nav_msgs/GetMap.h>
12 #include <cpswarm_msgs/AreaDivisionEvent.h>
13 #include <cpswarm_msgs/GetDouble.h>
14 #include <cpswarm_msgs/ArrayOfStates.h>
15 #include <cpswarm_msgs/StateEvent.h>
16 #include <swarmros/String.h>
17 #include "lib/area_division.h"
18 
19 using namespace std;
20 using namespace ros;
21 
25 typedef enum {
26  IDLE = 0, // this CPS is in a behavior state that does not require area division
27  INIT, // this CPS just changed to a behavior state that requires area division
28  ACTIVE, // this CPS is in a behavior state that requires area division
29  SYNC, // synchronization with the other CPSs is necessary
30  DIVIDE, // area division is required
31  DEINIT // this CPS just changed to a behavior state that does not require area division
32 } state_t;
33 
38 
43 
48 
53 
58 
63 
68 
73 
78 
83 
88 
93 
98 
102 string uuid;
103 
107 string behavior;
108 
113 
117 vector<string> behaviors;
118 
122 map<string, geometry_msgs::PoseStamped> swarm_pose;
123 
127 map<string, Time> swarm;
128 
133 
137 geometry_msgs::Pose pose;
138 
143 
147 nav_msgs::OccupancyGrid global_map;
148 
153 
158 
162 geometry_msgs::Vector3 translation;
163 
167 double resolution;
168 
173 
178 
183 
184 #endif // AREA_DIVISION_H
Publisher map_ds_pub
Publisher to visualize the downsampled map.
Definition: area_division.h:87
Publisher area_pub
Publisher to visualize the assigned area grid map.
Definition: area_division.h:77
bool visualize
Whether to publish the area division on a topic for visualization.
bool swarm_valid
Whether valid state information has been received from the other swarm members.
A class to divide the environment optimally among multiple cyber physical systems (CPSs)...
Publisher map_rot_pub
Publisher to visualize the rotated map.
Definition: area_division.h:82
double swarm_timeout
The time in seconds communication in the swarm can be delayed at most. Used to wait after an area div...
bool pose_valid
Whether a valid position has been received.
Subscriber division_sub
Subscriber to get area division requests from other CPSs.
Definition: area_division.h:62
bool behavior_valid
Whether a valid state has been received.
geometry_msgs::Pose pose
Current position of the CPS.
state_t state
The state of the area division node.
Definition: area_division.h:37
Publisher swarm_pub
Publisher to syncronize with other CPSs.
Definition: area_division.h:72
ServiceClient rotater_cli
Service client to get the angle which the area has to be rotated by.
Definition: area_division.h:92
Subscriber pose_sub
Subscriber to get CPS position.
Definition: area_division.h:47
Time sync_start
The time at which the synchronization for the area division started.
area_division * division
The object encapsulating the area division optimization algorithm.
map< string, Time > swarm
The UUIDs of the other swarm members.
nav_msgs::OccupancyGrid global_map
The complete grid map.
Subscriber map_sub
Subscriber to get grid map.
Definition: area_division.h:57
geometry_msgs::Vector3 translation
The translation by which the area has been shifted.
string uuid
UUID of this CPS.
vector< string > behaviors
The behavior states in which area division is active.
double resolution
The grid map underlying the area division will be downsampled to this resolution in meter / cell...
map< string, geometry_msgs::PoseStamped > swarm_pose
The positions of the other swarm members.
state_t
An enumeration for the state of the division.
Definition: area_division.h:25
Subscriber uuid_sub
Subscriber to get CPS UUID.
Definition: area_division.h:42
Publisher pos_pub
Publisher to stop the CPS.
Definition: area_division.h:67
bool map_valid
Whether a valid grid map has been received.
Subscriber swarm_sub
Subscriber to get information about other CPSs in the swarm.
Definition: area_division.h:52
string behavior
The current behavior state of this CPS.
Rate * rate
ROS rate object for controlling loop rates.
Definition: area_division.h:97


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