coverage_path.h
Go to the documentation of this file.
1 #ifndef COVERAGE_PATH_H
2 #define COVERAGE_PATH_H
3 
4 #include <ros/ros.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>
16 #include "lib/spanning_tree.h"
17 #include "lib/mst_path.h"
18 
19 using namespace std;
20 using namespace ros;
21 
26 
31 
36 
41 
46 
51 
55 nav_msgs::OccupancyGrid area;
56 
60 bool map_valid;
61 
66 
71 
75 map<string, Time> swarm;
76 
80 double resolution;
81 
85 bool visualize;
86 
91 
95 bool vertical;
96 
101 
106 
111 
115 vector<string> behaviors;
116 
121 
122 #endif // COVERAGE_PATH_H
nav_msgs::OccupancyGrid area
The grid map representing the environment to be covered.
Definition: coverage_path.h:55
Subscriber swarm_sub
Subscriber to get information about other CPSs in the swarm.
Definition: coverage_path.h:45
Publisher path_publisher
Publisher to visualize the coverage path.
Definition: coverage_path.h:25
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.
Definition: coverage_path.h:35
double resolution
The grid map underlying the path planning will be downsampled to this resolution in meter / cell...
Definition: coverage_path.h:80
A class that generates a minimum-spanning-tree (MST) graph for a given grid map.
Definition: spanning_tree.h:20
ServiceClient area_getter
Service client to get coordinates of the area to cover.
Definition: coverage_path.h:50
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.
Definition: coverage_path.h:30
Subscriber map_subscriber
Service client to get the assigned area.
Definition: coverage_path.h:40
bool vertical
Whether the sweeping pattern is vertical or horizontal.
Definition: coverage_path.h:95
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.
Definition: coverage_path.h:85
spanning_tree tree
The minimum-spanning-tree (MST) that defines the coverage path.
Definition: coverage_path.h:65
mst_path path
The coverage path.
Definition: coverage_path.h:70
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.
Definition: coverage_path.h:75
bool map_valid
Whether a valid grid map has been received.
Definition: coverage_path.h:60
An class to compute the coverage path based on a minimum-spanning-tree (MST).
Definition: mst_path.h:22
bool divide_area
Whether to divide the area among the CPSs before generating the path or to generate the path on the c...
Definition: coverage_path.h:90


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