Public Member Functions | Protected Attributes
bwi_mapper::VoronoiApproximator Class Reference

The voronoi approximator API. Inherits MapLoader to directly load a map from file and be able to draw a map. More...

#include <voronoi_approximator.h>

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

List of all members.

Public Member Functions

void drawOutput (cv::Mat &image)
 Draws the base map and voronoi points on to image. Should be only used for testing the output for Voronoi Approximator.
void drawVoronoiPoints (cv::Mat &image, uint32_t orig_x=0, uint32_t orig_y=0)
 Draw voronoi points onto image starting at (orig_x, orig_y)
void findVoronoiPoints (double threshold, bool use_naive=false, int sub_pixel_sampling=1)
 Computes the points that lie on the Voronoi Graph using an approximate strategy useful for voronoi approximation during mapping.
void printVoronoiPoints ()
 Prints information about all the voronoi points to screen. Used for testing the output for Voronoi Approximator.
 VoronoiApproximator (const std::string &fname)
 Constructor. Initializes map_resp_ from given file. Only used to call the base class constructor.

Protected Attributes

nav_msgs::OccupancyGrid inflated_map_
 inflated map used to throw out points too close to obstacle
bool initialized_
 Safety check to make sure findVoronoiPoints has been called.
std::vector< VoronoiPointvoronoi_points_
 the compute voronoi points are placed in here

Detailed Description

The voronoi approximator API. Inherits MapLoader to directly load a map from file and be able to draw a map.

Definition at line 57 of file voronoi_approximator.h.


Constructor & Destructor Documentation

bwi_mapper::VoronoiApproximator::VoronoiApproximator ( const std::string &  fname) [inline]

Constructor. Initializes map_resp_ from given file. Only used to call the base class constructor.

Parameters:
fnameabsolute or relative system file location for the YAML file

Definition at line 67 of file voronoi_approximator.h.


Member Function Documentation

Draws the base map and voronoi points on to image. Should be only used for testing the output for Voronoi Approximator.

Parameters:
imageOpenCV image we are drawing output on

Reimplemented in bwi_mapper::TopologicalMapper.

Definition at line 200 of file voronoi_approximator.cpp.

void bwi_mapper::VoronoiApproximator::drawVoronoiPoints ( cv::Mat &  image,
uint32_t  orig_x = 0,
uint32_t  orig_y = 0 
)

Draw voronoi points onto image starting at (orig_x, orig_y)

Parameters:
imageOpenCV image we are writing the map onto

Definition at line 231 of file voronoi_approximator.cpp.

void bwi_mapper::VoronoiApproximator::findVoronoiPoints ( double  threshold,
bool  is_naive = false,
int  sub_pixel_sampling = 1 
)

Computes the points that lie on the Voronoi Graph using an approximate strategy useful for voronoi approximation during mapping.

Parameters:
thresholdminimum obstacle distance in meters Any point which is less than threshold away from an obstacle is rejected as a voronoi candidate. This allows for not caring about minor breaks in a wall which can happen for any SLAM algorithm

Definition at line 57 of file voronoi_approximator.cpp.

Prints information about all the voronoi points to screen. Used for testing the output for Voronoi Approximator.

Definition at line 214 of file voronoi_approximator.cpp.


Member Data Documentation

nav_msgs::OccupancyGrid bwi_mapper::VoronoiApproximator::inflated_map_ [protected]

inflated map used to throw out points too close to obstacle

Definition at line 108 of file voronoi_approximator.h.

Safety check to make sure findVoronoiPoints has been called.

Definition at line 111 of file voronoi_approximator.h.

the compute voronoi points are placed in here

Definition at line 105 of file voronoi_approximator.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