1 #ifndef AREA_DIVISION_H 2 #define AREA_DIVISION_H 7 #include <geometry_msgs/Pose.h> 8 #include <geometry_msgs/PoseStamped.h> 9 #include <nav_msgs/OccupancyGrid.h> 10 #include <nav_msgs/GetMap.h> 11 #include <cpswarm_msgs/AreaDivisionEvent.h> 12 #include <swarmros/String.h> 97 #endif // AREA_DIVISION_H 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 position information has been received from the other swarm members.
A class to divide the environment optimally among multiple cyber physical systems (CPSs)...
double swarm_timeout
The time in seconds to wait after an area division event before starting the area division...
bool pose_valid
Whether a valid position has been received.
nav_msgs::OccupancyGrid gridmap
The complete grid map.
geometry_msgs::Pose pose
Current position of the CPS.
Publisher swarm_pub
Publisher to syncronize with other CPSs.
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.
string uuid
UUID of this CPS.
map< string, geometry_msgs::PoseStamped > swarm_pose
The positions of the other swarm members.
Publisher pos_pub
Publisher to stop the CPS.
bool map_valid
Whether a valid grid map has been received.
bool reconfigure
Whether the swarm configuration has changed and the area needs to be divided again.
Rate * rate
ROS rate object for controlling loop rates.