Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
tuw_graph::Segment_Expander Class Reference

#include <segment_expander.h>

Classes

struct  greater1
 
class  Index
 

Public Member Functions

std::vector< std::vector< Eigen::Vector2d > > calcEndpoints (float *_potential)
 looks for crossings and saves all segment endpoints of it More...
 
std::vector< SegmentgetGraph (const std::vector< std::vector< Eigen::Vector2d >> &_endPoints, float *_potential, const float _min_length, float _optimizePixelsCrossing, const float _optimizePixelsEndSegments)
 returns a list of segments, which represent the found search graph More...
 
void Initialize (cv::Mat &_map, cv::Mat &_distField, cv::Mat &_voronoiPath)
 initializes the expander by setting the voronoi path map and distancefield More...
 
 Segment_Expander ()
 

Private Member Functions

void addExpansionCandidate (const Index &current, const Index &next, float *potential)
 
bool checkSegmentPoint (const Index &_point)
 
template<class T , class S , class C >
void clearpq (std::priority_queue< T, S, C > &q)
 
std::vector< Eigen::Vector2d > expandCrossing (const Index &i, float *_potential)
 
Eigen::Vector2d expandSegment (Index start, float *_potential, const std::vector< std::vector< Eigen::Vector2d >> &_endpoints)
 
float getMinSegmentWidth (const std::vector< Eigen::Vector2d > &_path)
 
std::vector< Eigen::Vector2d > getPath (const Index &start, float *_potential, const std::vector< std::vector< Eigen::Vector2d >> &_endpoints)
 
bool isEndpoint (Index &_current, const std::vector< std::vector< Eigen::Vector2d >> &_endpoints)
 
uint32_t nrOfNeighbours (uint32_t i) const
 
void optimizeSegments (std::vector< Segment > &_segments, float _maxPixelsCrossing, float _maxPixelsEndSeg)
 
void optimizeSegmentsAroundPoint (std::vector< Segment > &_segments, const Eigen::Vector2d &pt, float maxPixels, int startIndex)
 
void removeEndpoint (const Index &_current, std::vector< std::vector< Eigen::Vector2d >> &_endpoints)
 
void removeSegmentFromList (const uint32_t _id, std::vector< Segment > &_segments)
 
const std::vector< tuw_graph::SegmentsplitPath (const std::vector< Eigen::Vector2d > &_path, const float _minimum_length)
 

Private Attributes

std::unique_ptr< float[]> distance_field_
 
bool findEdgeSegments_ = true
 
std::unique_ptr< int8_t[]> global_map_
 
int ns_
 
int nx_
 
int ny_
 
std::priority_queue< Index, std::vector< Index >, greater1queue_
 
std::unique_ptr< int8_t[]> voronoi_graph_
 

Detailed Description

Definition at line 43 of file segment_expander.h.

Constructor & Destructor Documentation

tuw_graph::Segment_Expander::Segment_Expander ( )

Definition at line 34 of file segment_expander.cpp.

Member Function Documentation

void tuw_graph::Segment_Expander::addExpansionCandidate ( const Index current,
const Index next,
float *  potential 
)
private

Definition at line 548 of file segment_expander.cpp.

std::vector< std::vector< Eigen::Vector2d > > tuw_graph::Segment_Expander::calcEndpoints ( float *  _potential)

looks for crossings and saves all segment endpoints of it

Parameters
_potentialvoronoi map potential
Returns
a list of crossings which contains all endpoints of the crossing

Definition at line 323 of file segment_expander.cpp.

bool tuw_graph::Segment_Expander::checkSegmentPoint ( const Index _point)
private

Definition at line 353 of file segment_expander.cpp.

template<class T , class S , class C >
void tuw_graph::Segment_Expander::clearpq ( std::priority_queue< T, S, C > &  q)
inlineprivate

Definition at line 81 of file segment_expander.h.

std::vector< Eigen::Vector2d > tuw_graph::Segment_Expander::expandCrossing ( const Index i,
float *  _potential 
)
private

Definition at line 498 of file segment_expander.cpp.

Eigen::Vector2d tuw_graph::Segment_Expander::expandSegment ( Segment_Expander::Index  _start,
float *  _potential,
const std::vector< std::vector< Eigen::Vector2d >> &  _endpoints 
)
private

Definition at line 439 of file segment_expander.cpp.

std::vector< Segment > tuw_graph::Segment_Expander::getGraph ( const std::vector< std::vector< Eigen::Vector2d >> &  _endPoints,
float *  _potential,
const float  _min_length,
float  _optimizePixelsCrossing,
const float  _optimizePixelsEndSegments 
)

returns a list of segments, which represent the found search graph

Parameters
_endPointsa list of all found endpoints (list of crossings which contain a set of endpoints)
_potentialpotential used to expand the pats
_min_lengththe minimum length a segment has to have (max = _min_length * 2 - epsilon)
_optimizePixelsCrossingif crossings have less distance than _optimizePixelsCrossing to each other they are merged
_optimizePixelsEndSegmentsif a end segment has less length than this var it is removed
Returns
a list of segments representing the graph

Definition at line 241 of file segment_expander.cpp.

float tuw_graph::Segment_Expander::getMinSegmentWidth ( const std::vector< Eigen::Vector2d > &  _path)
private

Definition at line 305 of file segment_expander.cpp.

std::vector< Eigen::Vector2d > tuw_graph::Segment_Expander::getPath ( const Index start,
float *  _potential,
const std::vector< std::vector< Eigen::Vector2d >> &  _endpoints 
)
private

Definition at line 375 of file segment_expander.cpp.

void tuw_graph::Segment_Expander::Initialize ( cv::Mat &  _map,
cv::Mat &  _distField,
cv::Mat &  _voronoiPath 
)

initializes the expander by setting the voronoi path map and distancefield

Parameters
_mapthe map
_distFieldthe distance_field generated from the map (e.g.: opencv distance_transform)
_voronoiPaththe generated voronoi path out of the distance field (e.g.: ridge following; zhang suen thinning...)

Definition at line 38 of file segment_expander.cpp.

bool tuw_graph::Segment_Expander::isEndpoint ( Segment_Expander::Index _current,
const std::vector< std::vector< Eigen::Vector2d >> &  _endpoints 
)
private

Definition at line 662 of file segment_expander.cpp.

uint32_t tuw_graph::Segment_Expander::nrOfNeighbours ( uint32_t  i) const
private

Definition at line 578 of file segment_expander.cpp.

void tuw_graph::Segment_Expander::optimizeSegments ( std::vector< Segment > &  _segments,
float  _maxPixelsCrossing,
float  _maxPixelsEndSeg 
)
private

Definition at line 61 of file segment_expander.cpp.

void tuw_graph::Segment_Expander::optimizeSegmentsAroundPoint ( std::vector< Segment > &  _segments,
const Eigen::Vector2d &  pt,
float  maxPixels,
int  startIndex 
)
private

Definition at line 121 of file segment_expander.cpp.

void tuw_graph::Segment_Expander::removeEndpoint ( const Index _current,
std::vector< std::vector< Eigen::Vector2d >> &  _endpoints 
)
private

Definition at line 635 of file segment_expander.cpp.

void tuw_graph::Segment_Expander::removeSegmentFromList ( const uint32_t  _id,
std::vector< Segment > &  _segments 
)
private

Definition at line 102 of file segment_expander.cpp.

const std::vector< tuw_graph::Segment > tuw_graph::Segment_Expander::splitPath ( const std::vector< Eigen::Vector2d > &  _path,
const float  _minimum_length 
)
private

Definition at line 199 of file segment_expander.cpp.

Member Data Documentation

std::unique_ptr<float[]> tuw_graph::Segment_Expander::distance_field_
private

Definition at line 74 of file segment_expander.h.

bool tuw_graph::Segment_Expander::findEdgeSegments_ = true
private

Definition at line 77 of file segment_expander.h.

std::unique_ptr<int8_t[]> tuw_graph::Segment_Expander::global_map_
private

Definition at line 76 of file segment_expander.h.

int tuw_graph::Segment_Expander::ns_
private

Definition at line 78 of file segment_expander.h.

int tuw_graph::Segment_Expander::nx_
private

Definition at line 78 of file segment_expander.h.

int tuw_graph::Segment_Expander::ny_
private

Definition at line 78 of file segment_expander.h.

std::priority_queue<Index, std::vector<Index>, greater1> tuw_graph::Segment_Expander::queue_
private

Definition at line 133 of file segment_expander.h.

std::unique_ptr<int8_t[]> tuw_graph::Segment_Expander::voronoi_graph_
private

Definition at line 75 of file segment_expander.h.


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


tuw_voronoi_graph
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:44