1 #ifndef SPANNING_TREE_H 2 #define SPANNING_TREE_H 5 #include <unordered_set> 9 #include <geometry_msgs/PoseArray.h> 10 #include <geometry_msgs/Vector3.h> 11 #include <nav_msgs/OccupancyGrid.h> 32 vector<edge> get_mst_edges ();
38 geometry_msgs::PoseArray get_tree ();
45 void initialize_graph (nav_msgs::OccupancyGrid gridmap,
bool vertical =
false,
bool connect4 =
true);
59 void add_edge (
int from,
int to,
int cost);
67 bool different_sets (
int a,
int b);
72 vector<unordered_set<int>>
nodes;
87 nav_msgs::OccupancyGrid
map;
105 #endif // SPANNING_TREE_H nav_msgs::OccupancyGrid map
The grid map that needs to be covered by the MST.
vector< edge > mst_edges
Edges in Minimal-Spanning Tree.
A struct that provides the comparison of edge objects. It allows sorting of edges for priority queues...
A class that generates a minimum-spanning-tree (MST) graph for a given grid map.
geometry_msgs::Vector3 translation
The translation of the output tree.
bool vertical
Whether the sweeping pattern is vertical or horizontal.
vector< unordered_set< int > > nodes
The sets of connected vertices.
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.
double rotation
The rotation of the output tree.