Public Member Functions | Public Attributes
bwi_mapper::VoronoiPoint Class Reference

#include <voronoi_point.h>

Inheritance diagram for bwi_mapper::VoronoiPoint:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addBasisCandidate (const Point2d &candidate, uint32_t threshold, const nav_msgs::OccupancyGrid &map, bool use_naive)
 Attempts to add a basis candidate to this voronoi point. The basis candidate is only added if and only if it is 2 * threshhold away from an existing basis for that point, and is not too close to existing basis point in obstacle space If it is too close, then it is only retained if it is better than an existing basis, in which case the existing basis is thrown out.
 VoronoiPoint ()
 VoronoiPoint (int x, int y)
 VoronoiPoint (const Point2d &pt)

Public Attributes

float average_clearance
float basis_distance
std::vector< Point2dbasis_points
float critical_clearance_diff

Detailed Description

Definition at line 48 of file voronoi_point.h.


Constructor & Destructor Documentation

Definition at line 51 of file voronoi_point.h.

bwi_mapper::VoronoiPoint::VoronoiPoint ( int  x,
int  y 
) [inline]

Definition at line 52 of file voronoi_point.h.

Definition at line 53 of file voronoi_point.h.


Member Function Documentation

void bwi_mapper::VoronoiPoint::addBasisCandidate ( const Point2d candidate,
uint32_t  threshold,
const nav_msgs::OccupancyGrid &  map,
bool  use_naive 
)

Attempts to add a basis candidate to this voronoi point. The basis candidate is only added if and only if it is 2 * threshhold away from an existing basis for that point, and is not too close to existing basis point in obstacle space If it is too close, then it is only retained if it is better than an existing basis, in which case the existing basis is thrown out.

Parameters:
thresholdAny point having an obstacle closer than threshold is rejected as it is not useful, even if it might be a valid voronoi point

Definition at line 53 of file voronoi_point.cpp.


Member Data Documentation

/brief average clearance from all basis points - used after all basis points have been computed

Definition at line 65 of file voronoi_point.h.

/brief minimum clearance to a basis point - used while computing basis points

Definition at line 60 of file voronoi_point.h.

Definition at line 55 of file voronoi_point.h.

/brief if this point is a critical point, how lower is the clearance of this point in comparison of its neighbours

Definition at line 70 of file voronoi_point.h.


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


bwi_mapper
Author(s): Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:14:35