Public Member Functions | Private Member Functions | Private Attributes | List of all members
spanning_tree Class Reference

A class that generates a minimum-spanning-tree (MST) graph for a given grid map. More...

#include <spanning_tree.h>

Public Member Functions

void construct ()
 Generate the MST using Kruskal's algorithm. More...
 
vector< edgeget_mst_edges ()
 Get the edges of the MST. More...
 
geometry_msgs::PoseArray get_tree ()
 Get the generated MST for visualization. More...
 
void initialize_graph (nav_msgs::OccupancyGrid gridmap, bool vertical=false, bool connect4=true)
 Initialize the internal tree structure from a given grid map. More...
 
 spanning_tree ()
 Constructor. More...
 

Private Member Functions

void add_edge (int from, int to, int cost)
 Add an edge to the tree. More...
 
bool different_sets (int a, int b)
 Check whether two vertices are in different sets. More...
 

Private Attributes

priority_queue< edge, vector< edge >, compare_edgeedges
 Priority queue of edge objects sorted by cost. More...
 
nav_msgs::OccupancyGrid map
 The grid map that needs to be covered by the MST. More...
 
vector< edgemst_edges
 Edges in Minimal-Spanning Tree. More...
 
vector< unordered_set< int > > nodes
 The sets of connected vertices. More...
 
double rotation
 The rotation of the output tree. More...
 
geometry_msgs::Vector3 translation
 The translation of the output tree. More...
 
bool vertical
 Whether the sweeping pattern is vertical or horizontal. More...
 

Detailed Description

A class that generates a minimum-spanning-tree (MST) graph for a given grid map.

Definition at line 20 of file spanning_tree.h.

Constructor & Destructor Documentation

spanning_tree::spanning_tree ( )

Constructor.

Definition at line 3 of file spanning_tree.cpp.

Member Function Documentation

void spanning_tree::add_edge ( int  from,
int  to,
int  cost 
)
private

Add an edge to the tree.

Parameters
fromThe starting vertex.
toThe ending vertex.
costThe cost of the edge.

Definition at line 119 of file spanning_tree.cpp.

void spanning_tree::construct ( )

Generate the MST using Kruskal's algorithm.

Definition at line 93 of file spanning_tree.cpp.

bool spanning_tree::different_sets ( int  a,
int  b 
)
private

Check whether two vertices are in different sets.

Parameters
aThe first vertex.
bThe second vertex.
Returns
True if the vertices are in different connected components, i.e., the set for vertex a is different from that for vertex b.

Definition at line 133 of file spanning_tree.cpp.

vector< edge > spanning_tree::get_mst_edges ( )

Get the edges of the MST.

Returns
A vector with all edges of the MST.

Definition at line 7 of file spanning_tree.cpp.

geometry_msgs::PoseArray spanning_tree::get_tree ( )

Get the generated MST for visualization.

Returns
An array of poses that represent the vertices of the tree.

Definition at line 12 of file spanning_tree.cpp.

void spanning_tree::initialize_graph ( nav_msgs::OccupancyGrid  gridmap,
bool  vertical = false,
bool  connect4 = true 
)

Initialize the internal tree structure from a given grid map.

Parameters
verticalWhether the sweeping pattern is vertical or horizontal. Default horizontal.
connect4Whether only the von Neumann neighborhood is considered. Default true.

Definition at line 39 of file spanning_tree.cpp.

Member Data Documentation

priority_queue<edge, vector<edge>, compare_edge> spanning_tree::edges
private

Priority queue of edge objects sorted by cost.

Definition at line 77 of file spanning_tree.h.

nav_msgs::OccupancyGrid spanning_tree::map
private

The grid map that needs to be covered by the MST.

Definition at line 87 of file spanning_tree.h.

vector<edge> spanning_tree::mst_edges
private

Edges in Minimal-Spanning Tree.

Definition at line 82 of file spanning_tree.h.

vector<unordered_set<int> > spanning_tree::nodes
private

The sets of connected vertices.

Definition at line 72 of file spanning_tree.h.

double spanning_tree::rotation
private

The rotation of the output tree.

Definition at line 92 of file spanning_tree.h.

geometry_msgs::Vector3 spanning_tree::translation
private

The translation of the output tree.

Definition at line 97 of file spanning_tree.h.

bool spanning_tree::vertical
private

Whether the sweeping pattern is vertical or horizontal.

Definition at line 102 of file spanning_tree.h.


The documentation for this class was generated from the following files:


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