spanning_tree.h
Go to the documentation of this file.
1 #ifndef SPANNING_TREE_H
2 #define SPANNING_TREE_H
3 
4 #include <queue>
5 #include <unordered_set>
6 #include <valarray>
7 #include <ros/ros.h>
8 #include <tf2/utils.h>
9 #include <geometry_msgs/PoseArray.h>
10 #include <geometry_msgs/Vector3.h>
11 #include <nav_msgs/OccupancyGrid.h>
12 #include "lib/edge.h"
13 
14 using namespace std;
15 using namespace ros;
16 
21 {
22 public:
26  spanning_tree ();
27 
32  vector<edge> get_mst_edges ();
33 
38  geometry_msgs::PoseArray get_tree ();
39 
45  void initialize_graph (nav_msgs::OccupancyGrid gridmap, bool vertical = false, bool connect4 = true);
46 
50  void construct ();
51 
52 private:
59  void add_edge (int from, int to, int cost);
60 
67  bool different_sets (int a, int b);
68 
72  vector<unordered_set<int>> nodes;
73 
77  priority_queue<edge, vector<edge>, compare_edge> edges;
78 
82  vector<edge> mst_edges;
83 
87  nav_msgs::OccupancyGrid map;
88 
92  double rotation;
93 
97  geometry_msgs::Vector3 translation;
98 
102  bool vertical;
103 };
104 
105 #endif // SPANNING_TREE_H
nav_msgs::OccupancyGrid map
The grid map that needs to be covered by the MST.
Definition: spanning_tree.h:87
vector< edge > mst_edges
Edges in Minimal-Spanning Tree.
Definition: spanning_tree.h:82
A struct that provides the comparison of edge objects. It allows sorting of edges for priority queues...
Definition: edge.h:52
A class that generates a minimum-spanning-tree (MST) graph for a given grid map.
Definition: spanning_tree.h:20
geometry_msgs::Vector3 translation
The translation of the output tree.
Definition: spanning_tree.h:97
bool vertical
Whether the sweeping pattern is vertical or horizontal.
Definition: coverage_path.h:95
vector< unordered_set< int > > nodes
The sets of connected vertices.
Definition: spanning_tree.h:72
bool vertical
Whether the sweeping pattern is vertical or horizontal.
priority_queue< edge, vector< edge >, compare_edge > edges
Priority queue of edge objects sorted by cost.
Definition: spanning_tree.h:77
double rotation
The rotation of the output tree.
Definition: spanning_tree.h:92


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