1 #ifndef COVERAGE_PATH_H 2 #define COVERAGE_PATH_H 5 #include <geometry_msgs/Pose.h> 6 #include <geometry_msgs/PoseStamped.h> 7 #include <geometry_msgs/PointStamped.h> 8 #include <geometry_msgs/PoseArray.h> 9 #include <geometry_msgs/Vector3.h> 10 #include <nav_msgs/Path.h> 11 #include <nav_msgs/OccupancyGrid.h> 12 #include <nav_msgs/GetPlan.h> 13 #include <cpswarm_msgs/GetWaypoint.h> 14 #include <cpswarm_msgs/GetPoints.h> 15 #include <cpswarm_msgs/ArrayOfStates.h> 55 nav_msgs::OccupancyGrid
area;
122 #endif // COVERAGE_PATH_H
nav_msgs::OccupancyGrid area
The grid map representing the environment to be covered.
Subscriber swarm_sub
Subscriber to get information about other CPSs in the swarm.
Publisher path_publisher
Publisher to visualize the coverage path.
bool turning_points
Whether there are only waypoints at turning points of the path or also waypoints regularly spaced on ...
bool swarm_path
Whether to regnerate the path when new CPSs join or leave the swarm.
Publisher mst_publisher
Publisher to visualize the minimum spanning tree.
double resolution
The grid map underlying the path planning will be downsampled to this resolution in meter / cell...
A class that generates a minimum-spanning-tree (MST) graph for a given grid map.
ServiceClient area_getter
Service client to get coordinates of the area to cover.
double swarm_timeout
The time in seconds communication in the swarm can be delayed at most. Used to wait after an area div...
Publisher wp_publisher
Publisher to visualize the current waypoint.
Subscriber map_subscriber
Service client to get the assigned area.
bool vertical
Whether the sweeping pattern is vertical or horizontal.
vector< string > behaviors
The behavior states in which CPSs are considered part of the swarm.
bool visualize
Whether to publish the coverage path on a topic for visualization.
spanning_tree tree
The minimum-spanning-tree (MST) that defines the coverage path.
mst_path path
The coverage path.
bool reconfigure
Whether the swarm configuration has changed which requires a replanning of the path.
map< string, Time > swarm
The UUIDs of the other swarm members.
bool map_valid
Whether a valid grid map has been received.
An class to compute the coverage path based on a minimum-spanning-tree (MST).
bool divide_area
Whether to divide the area among the CPSs before generating the path or to generate the path on the c...