mst_path.h
Go to the documentation of this file.
1 #ifndef MST_PATH_H
2 #define MST_PATH_H
3 
4 #include <deque>
5 #include <valarray>
6 #include <unordered_set>
7 #include <ros/ros.h>
8 #include <tf2/utils.h>
9 #include <geometry_msgs/Point.h>
10 #include <geometry_msgs/PoseArray.h>
11 #include <geometry_msgs/Vector3.h>
12 #include <nav_msgs/OccupancyGrid.h>
13 #include <nav_msgs/Path.h>
14 #include "lib/edge.h"
15 
16 using namespace std;
17 using namespace ros;
18 
22 class mst_path
23 {
24 public:
28  mst_path ();
29 
35  bool generate_path (geometry_msgs::Point start);
36 
41  nav_msgs::Path get_path ();
42 
49  geometry_msgs::Point get_waypoint (geometry_msgs::Point position, double tolerance);
50 
57  void initialize_graph (nav_msgs::OccupancyGrid gridmap, bool vertical = false, bool connect4 = true);
58 
66  void initialize_map (geometry_msgs::Point origin, double rotation, double width, double height);
67 
72  void initialize_tree (vector<edge> mst);
73 
77  void reduce ();
78 
83  bool valid ();
84 
85 private:
92  void add_edge(int from, int to, int cost);
93 
100  double dist (geometry_msgs::Point p1, geometry_msgs::Point p2);
101 
107  geometry_msgs::Point get_wp (int offset=0);
108 
113  void remove_edge (edge e);
114 
118  deque<geometry_msgs::Point> path;
119 
123  unordered_set<edge, hash_edge> edges;
124 
128  vector<unordered_set<int>> nodes;
129 
133  nav_msgs::OccupancyGrid map;
134 
138  int wp;
139 
143  geometry_msgs::Point origin;
144 
148  double rotation;
149 
153  double width;
154 
158  double height;
159 
163  bool vertical;
164 };
165 
166 #endif // MST_PATH_H
bool get_path(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res)
Callback function to get the coverage path.
bool get_waypoint(cpswarm_msgs::GetWaypoint::Request &req, cpswarm_msgs::GetWaypoint::Response &res)
Callback function to get the current waypoint of the path.
ROSCPP_DECL void start()
double rotation
The rotation of the map.
Definition: mst_path.h:148
bool generate_path(geometry_msgs::Point start)
Generate an optimal coverage path for a given area.
int wp
The current way point.
Definition: mst_path.h:138
double height
Height of the area to cover.
Definition: mst_path.h:158
A class for representing edges.
Definition: edge.h:9
bool vertical
Whether the sweeping pattern is vertical or horizontal.
Definition: coverage_path.h:95
double width
Width of the area to cover.
Definition: mst_path.h:153
vector< unordered_set< int > > nodes
The sets of connected vertices.
Definition: mst_path.h:128
nav_msgs::OccupancyGrid map
The grid map that needs to be covered by the MST path.
Definition: mst_path.h:133
deque< geometry_msgs::Point > path
The boustrophedon path.
Definition: mst_path.h:118
An class to compute the coverage path based on a minimum-spanning-tree (MST).
Definition: mst_path.h:22
geometry_msgs::Point origin
Coordinate of the bottom left bounding point of the area.
Definition: mst_path.h:143
bool vertical
Whether the sweeping pattern is vertical or horizontal.
Definition: mst_path.h:163
unordered_set< edge, hash_edge > edges
Priority queue of edge objects sorted by cost.
Definition: mst_path.h:123


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