1 #ifndef AREA_DIVISION_H 2 #define AREA_DIVISION_H 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> 184 #endif // AREA_DIVISION_H Publisher map_ds_pub
Publisher to visualize the downsampled map.
Publisher area_pub
Publisher to visualize the assigned area grid map.
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.
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.
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.
Publisher swarm_pub
Publisher to syncronize with other CPSs.
ServiceClient rotater_cli
Service client to get the angle which the area has to be rotated by.
Subscriber pose_sub
Subscriber to get CPS position.
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.
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.
Subscriber uuid_sub
Subscriber to get CPS UUID.
Publisher pos_pub
Publisher to stop the CPS.
bool map_valid
Whether a valid grid map has been received.
Subscriber swarm_sub
Subscriber to get information about other CPSs in the swarm.
string behavior
The current behavior state of this CPS.
Rate * rate
ROS rate object for controlling loop rates.