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

An class to compute the coverage path based on a minimum-spanning-tree (MST). More...

#include <mst_path.h>

Public Member Functions

bool generate_path (geometry_msgs::Point start)
 Generate all way points for the path. More...
 
nav_msgs::Path get_path ()
 Get the complete path. More...
 
geometry_msgs::Point get_waypoint (geometry_msgs::Point position, double tolerance)
 Get the current waypoint and possibly select next waypoint, if close enough. More...
 
void initialize_graph (nav_msgs::OccupancyGrid gridmap, bool vertical=false, bool connect4=true)
 Initialize the internal graph structure that represents the area division. More...
 
void initialize_map (geometry_msgs::Point origin, double rotation, double width, double height)
 Initialize properties of the area to be covered. More...
 
void initialize_tree (vector< edge > mst)
 Remove edges of the graph that overlap with the tree. More...
 
 mst_path ()
 Constructor. More...
 
void reduce ()
 Remove waypoints that are within straight line segments of the path. Only keep turning points of the path. More...
 
bool valid ()
 Check whether the current waypoint index is valid. More...
 

Private Member Functions

void add_edge (int from, int to, int cost)
 Add an edge to the tree graph. More...
 
double dist (geometry_msgs::Point p1, geometry_msgs::Point p2)
 Calculate the distance between two points. More...
 
geometry_msgs::Point get_wp (int offset=0)
 Get the current way point. More...
 
void remove_edge (edge e)
 Remove an edge from the tree graph. More...
 

Private Attributes

unordered_set< edge, hash_edgeedges
 Priority queue of edge objects sorted by cost. More...
 
double height
 Height of the area to cover. More...
 
nav_msgs::OccupancyGrid map
 The grid map that needs to be covered by the MST path. More...
 
vector< unordered_set< int > > nodes
 The sets of connected vertices. More...
 
geometry_msgs::Point origin
 Coordinate of the bottom left bounding point of the area. More...
 
deque< geometry_msgs::Point > path
 The boustrophedon path. More...
 
double rotation
 The rotation of the map. More...
 
bool vertical
 Whether the sweeping pattern is vertical or horizontal. More...
 
double width
 Width of the area to cover. More...
 
int wp
 The current way point. More...
 

Detailed Description

An class to compute the coverage path based on a minimum-spanning-tree (MST).

Definition at line 22 of file mst_path.h.

Constructor & Destructor Documentation

mst_path::mst_path ( )

Constructor.

Definition at line 3 of file mst_path.cpp.

Member Function Documentation

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

Add an edge to the tree graph.

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

Definition at line 269 of file mst_path.cpp.

double mst_path::dist ( geometry_msgs::Point  p1,
geometry_msgs::Point  p2 
)
private

Calculate the distance between two points.

Parameters
p1The first point.
p2The second point.
Returns
The straight line distance between both points.

Definition at line 280 of file mst_path.cpp.

bool mst_path::generate_path ( geometry_msgs::Point  start)

Generate all way points for the path.

Parameters
startThe current position of the CPS.
Returns
Whether the generation was successful.

Definition at line 7 of file mst_path.cpp.

nav_msgs::Path mst_path::get_path ( )

Get the complete path.

Returns
The path as vector of poses.

Definition at line 101 of file mst_path.cpp.

geometry_msgs::Point mst_path::get_waypoint ( geometry_msgs::Point  position,
double  tolerance 
)

Get the current waypoint and possibly select next waypoint, if close enough.

Parameters
positionThe current position of the CPS.
toleranceThe distance to the current waypoint below which the next waypoint is selected.
Returns
A waypoint for the CPS to navigate to.

Definition at line 123 of file mst_path.cpp.

geometry_msgs::Point mst_path::get_wp ( int  offset = 0)
private

Get the current way point.

Parameters
offsetThe index offset to the current waypoint.
Returns
The way point, if a valid offset was given. An empty point otherwise.

Definition at line 285 of file mst_path.cpp.

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

Initialize the internal graph structure that represents the area division.

Parameters
graphgridmap The grid map for which the paths are generated.
verticalWhether the sweeping pattern is vertical or horizontal. Default horizontal.
connect4Whether only the von Neumann neighborhood is considered. Default true.

Definition at line 139 of file mst_path.cpp.

void mst_path::initialize_map ( geometry_msgs::Point  origin,
double  rotation,
double  width,
double  height 
)

Initialize properties of the area to be covered.

Parameters
originCoordinate of the bottom left point of the area.
rotationThe angle by which the map has been rotated.
widthThe width of the area.
heightThe height of the area.

Definition at line 201 of file mst_path.cpp.

void mst_path::initialize_tree ( vector< edge mst)

Remove edges of the graph that overlap with the tree.

Parameters
mstThe edges that define the tree.

Definition at line 216 of file mst_path.cpp.

void mst_path::reduce ( )

Remove waypoints that are within straight line segments of the path. Only keep turning points of the path.

Definition at line 243 of file mst_path.cpp.

void mst_path::remove_edge ( edge  e)
private

Remove an edge from the tree graph.

Parameters
eThe edge to remove.

Definition at line 302 of file mst_path.cpp.

bool mst_path::valid ( )

Check whether the current waypoint index is valid.

Returns
True, if the waypoint index is within the limits of the path, false otherwise.

Definition at line 264 of file mst_path.cpp.

Member Data Documentation

unordered_set<edge, hash_edge> mst_path::edges
private

Priority queue of edge objects sorted by cost.

Definition at line 123 of file mst_path.h.

double mst_path::height
private

Height of the area to cover.

Definition at line 158 of file mst_path.h.

nav_msgs::OccupancyGrid mst_path::map
private

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

Definition at line 133 of file mst_path.h.

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

The sets of connected vertices.

Definition at line 128 of file mst_path.h.

geometry_msgs::Point mst_path::origin
private

Coordinate of the bottom left bounding point of the area.

Definition at line 143 of file mst_path.h.

deque<geometry_msgs::Point> mst_path::path
private

The boustrophedon path.

Definition at line 118 of file mst_path.h.

double mst_path::rotation
private

The rotation of the map.

Definition at line 148 of file mst_path.h.

bool mst_path::vertical
private

Whether the sweeping pattern is vertical or horizontal.

Definition at line 163 of file mst_path.h.

double mst_path::width
private

Width of the area to cover.

Definition at line 153 of file mst_path.h.

int mst_path::wp
private

The current way point.

Definition at line 138 of file mst_path.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