#include <ros/ros.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/Vector3.h>
#include <nav_msgs/Path.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/GetPlan.h>
#include <cpswarm_msgs/GetWaypoint.h>
#include <cpswarm_msgs/GetPoints.h>
#include <cpswarm_msgs/ArrayOfStates.h>
#include "lib/spanning_tree.h"
#include "lib/mst_path.h"
Go to the source code of this file.
Variables | |
nav_msgs::OccupancyGrid | area |
The grid map representing the environment to be covered. More... | |
ServiceClient | area_getter |
Service client to get coordinates of the area to cover. More... | |
vector< string > | behaviors |
The behavior states in which CPSs are considered part of the swarm. More... | |
bool | divide_area |
Whether to divide the area among the CPSs before generating the path or to generate the path on the complete map. More... | |
Subscriber | map_subscriber |
Service client to get the assigned area. More... | |
bool | map_valid |
Whether a valid grid map has been received. More... | |
Publisher | mst_publisher |
Publisher to visualize the minimum spanning tree. More... | |
mst_path | path |
The coverage path. More... | |
Publisher | path_publisher |
Publisher to visualize the coverage path. More... | |
bool | reconfigure |
Whether the swarm configuration has changed which requires a replanning of the path. More... | |
double | resolution |
The grid map underlying the path planning will be downsampled to this resolution in meter / cell. More... | |
map< string, Time > | swarm |
The UUIDs of the other swarm members. More... | |
bool | swarm_path |
Whether to regnerate the path when new CPSs join or leave the swarm. More... | |
Subscriber | swarm_sub |
Subscriber to get information about other CPSs in the swarm. More... | |
double | swarm_timeout |
The time in seconds communication in the swarm can be delayed at most. Used to wait after an area division event before starting the area division or time after which it is assumed that a swarm member has left the swarm if no position update has been received. More... | |
spanning_tree | tree |
The minimum-spanning-tree (MST) that defines the coverage path. More... | |
bool | turning_points |
Whether there are only waypoints at turning points of the path or also waypoints regularly spaced on straight line segments of the path. More... | |
bool | vertical |
Whether the sweeping pattern is vertical or horizontal. More... | |
bool | visualize |
Whether to publish the coverage path on a topic for visualization. More... | |
Publisher | wp_publisher |
Publisher to visualize the current waypoint. More... | |
nav_msgs::OccupancyGrid area |
The grid map representing the environment to be covered.
Definition at line 55 of file coverage_path.h.
ServiceClient area_getter |
Service client to get coordinates of the area to cover.
Definition at line 50 of file coverage_path.h.
vector<string> behaviors |
The behavior states in which CPSs are considered part of the swarm.
Definition at line 115 of file coverage_path.h.
bool divide_area |
Whether to divide the area among the CPSs before generating the path or to generate the path on the complete map.
Definition at line 90 of file coverage_path.h.
Subscriber map_subscriber |
Service client to get the assigned area.
Definition at line 40 of file coverage_path.h.
bool map_valid |
Whether a valid grid map has been received.
Definition at line 60 of file coverage_path.h.
Publisher mst_publisher |
Publisher to visualize the minimum spanning tree.
Definition at line 35 of file coverage_path.h.
mst_path path |
The coverage path.
Definition at line 70 of file coverage_path.h.
Publisher path_publisher |
Publisher to visualize the coverage path.
Definition at line 25 of file coverage_path.h.
bool reconfigure |
Whether the swarm configuration has changed which requires a replanning of the path.
Definition at line 120 of file coverage_path.h.
double resolution |
The grid map underlying the path planning will be downsampled to this resolution in meter / cell.
Definition at line 80 of file coverage_path.h.
map<string, Time> swarm |
The UUIDs of the other swarm members.
Definition at line 75 of file coverage_path.h.
bool swarm_path |
Whether to regnerate the path when new CPSs join or leave the swarm.
Definition at line 105 of file coverage_path.h.
Subscriber swarm_sub |
Subscriber to get information about other CPSs in the swarm.
Definition at line 45 of file coverage_path.h.
double swarm_timeout |
The time in seconds communication in the swarm can be delayed at most. Used to wait after an area division event before starting the area division or time after which it is assumed that a swarm member has left the swarm if no position update has been received.
Definition at line 110 of file coverage_path.h.
spanning_tree tree |
The minimum-spanning-tree (MST) that defines the coverage path.
Definition at line 65 of file coverage_path.h.
bool turning_points |
Whether there are only waypoints at turning points of the path or also waypoints regularly spaced on straight line segments of the path.
Definition at line 100 of file coverage_path.h.
bool vertical |
Whether the sweeping pattern is vertical or horizontal.
Definition at line 95 of file coverage_path.h.
bool visualize |
Whether to publish the coverage path on a topic for visualization.
Definition at line 85 of file coverage_path.h.
Publisher wp_publisher |
Publisher to visualize the current waypoint.
Definition at line 30 of file coverage_path.h.