#include <ros/ros.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/PointStamped.h>
#include <nav_msgs/Path.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/GetMap.h>
#include <nav_msgs/GetPlan.h>
#include <cpswarm_msgs/GetWaypoint.h>
#include <cpswarm_msgs/ArrayOfStates.h>
#include <cpswarm_msgs/StateEvent.h>
#include "lib/spanning_tree.h"
#include "lib/mst_path.h"
Go to the source code of this file.
Variables | |
nav_msgs::OccupancyGrid | gridmap |
The grid map representing the environment to be covered. More... | |
ServiceClient | map_getter |
Service client to get the assigned area. More... | |
mst_path | path |
The coverage path. More... | |
Publisher | path_publisher |
Publisher to visualize the coverage path. More... | |
geometry_msgs::Pose | pose |
Current position of the CPS. More... | |
bool | pose_valid |
Whether a valid position has been received. More... | |
bool | reconfigure |
Whether the swarm configuration has changed which requires a replanning of the path. More... | |
string | state |
Current state of the CPS. More... | |
bool | state_valid |
Whether a valid state has been received. More... | |
map< string, Time > | swarm |
The UUIDs of the other swarm members. More... | |
double | swarm_timeout |
Time in seconds after which it is assumed that a swarm member has left the swarm if no position update has been received. More... | |
bool | swarm_valid |
Whether valid swarm information has been received. More... | |
spanning_tree | tree |
The minimum-spanning-tree (MST) that defines the coverage path. 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 gridmap |
The grid map representing the environment to be covered.
Definition at line 69 of file coverage_path.h.
ServiceClient map_getter |
Service client to get the assigned area.
Definition at line 34 of file coverage_path.h.
mst_path path |
The coverage path.
Definition at line 79 of file coverage_path.h.
Publisher path_publisher |
Publisher to visualize the coverage path.
Definition at line 24 of file coverage_path.h.
geometry_msgs::Pose pose |
Current position of the CPS.
Definition at line 39 of file coverage_path.h.
bool pose_valid |
Whether a valid position has been received.
Definition at line 44 of file coverage_path.h.
bool reconfigure |
Whether the swarm configuration has changed which requires a replanning of the path.
Definition at line 94 of file coverage_path.h.
string state |
Current state of the CPS.
Definition at line 49 of file coverage_path.h.
bool state_valid |
Whether a valid state has been received.
Definition at line 54 of file coverage_path.h.
map<string, Time> swarm |
The UUIDs of the other swarm members.
Definition at line 59 of file coverage_path.h.
double swarm_timeout |
Time in seconds after which it is assumed that a swarm member has left the swarm if no position update has been received.
Definition at line 84 of file coverage_path.h.
bool swarm_valid |
Whether valid swarm information has been received.
Definition at line 64 of file coverage_path.h.
spanning_tree tree |
The minimum-spanning-tree (MST) that defines the coverage path.
Definition at line 74 of file coverage_path.h.
bool visualize |
Whether to publish the coverage path on a topic for visualization.
Definition at line 89 of file coverage_path.h.
Publisher wp_publisher |
Publisher to visualize the current waypoint.
Definition at line 29 of file coverage_path.h.