Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
crossing_detector::CrossingDetector Class Reference

#include <crossing_detector.h>

Inheritance diagram for crossing_detector::CrossingDetector:
Inheritance graph
[legend]

List of all members.

Public Member Functions

Crossing crossingDescriptor (const PlaceProfile &profile, const bool normalize=false)
 CrossingDetector (const double frontier_width, const double max_frontier_angle=1.0)
vector< Frontier > frontiers (const PlaceProfile &profile, const bool normalize=false)
double getFrontierWidth () const
double getMaxFrontierAngle () const
double getMinRelevance () const
PlaceProfile getPlaceProfile () const
void setFrontierWidth (const double value)
void setMaxFrontierAngle (const double value)
void setMinRelevance (const double value)

Protected Member Functions

vector< Frontier > frontiers_ () const

Protected Attributes

PlaceProfile place_profile_
 PlaceProfile used to compute the crossing.

Private Member Functions

vector< PointdelaunayInput (const PlaceProfile &profile) const

Private Attributes

double frontier_width_
 Min. frontier width, i.e. space turough which a robot can go (m).
double max_frontier_angle_
double min_relevance_

Detailed Description

Definition at line 38 of file crossing_detector.h.


Constructor & Destructor Documentation

crossing_detector::CrossingDetector::CrossingDetector ( const double  frontier_width,
const double  max_frontier_angle = 1.0 
)

Definition at line 102 of file crossing_detector.cpp.


Member Function Documentation

Crossing crossing_detector::CrossingDetector::crossingDescriptor ( const PlaceProfile &  profile,
const bool  normalize = false 
)

Return a lama_msgs/Crossing message from analysis of a lama_msgs/PlaceProfile

profile[in] PlaceProfile message. normalize[in] true if the PlaceProfile should be normalized in a first step.

Definition at line 117 of file crossing_detector.cpp.

vector< Point > crossing_detector::CrossingDetector::delaunayInput ( const PlaceProfile &  profile) const [private]

Return a list of points suited for Delaunay

Definition at line 274 of file crossing_detector.cpp.

vector< Frontier > crossing_detector::CrossingDetector::frontiers ( const PlaceProfile &  profile,
const bool  normalize = false 
)

Return a list of frontiers.

Frontiers can be an excluded segment (or a series of them) or a normal segment.

profile[in] PlaceProfile message. normalize[in] true if the PlaceProfile should be normalized in a first step.

Definition at line 258 of file crossing_detector.cpp.

vector< Frontier > crossing_detector::CrossingDetector::frontiers_ ( ) const [protected]

Return frontiers computed from place_profile_.

Frontiers can be an excluded segment (or a series of them) or a normal segment. Uses place_profile_ as input.

Definition at line 199 of file crossing_detector.cpp.

Definition at line 47 of file crossing_detector.h.

Definition at line 50 of file crossing_detector.h.

Definition at line 53 of file crossing_detector.h.

Definition at line 56 of file crossing_detector.h.

void crossing_detector::CrossingDetector::setFrontierWidth ( const double  value) [inline]

Definition at line 48 of file crossing_detector.h.

void crossing_detector::CrossingDetector::setMaxFrontierAngle ( const double  value) [inline]

Definition at line 51 of file crossing_detector.h.

void crossing_detector::CrossingDetector::setMinRelevance ( const double  value) [inline]

Definition at line 54 of file crossing_detector.h.


Member Data Documentation

Min. frontier width, i.e. space turough which a robot can go (m).

Definition at line 69 of file crossing_detector.h.

Max. angle between frontier and line from robot to frontier (rad). 0 means that the angle between the line from robot to frontier middle and the frontier is 90 deg.

Definition at line 70 of file crossing_detector.h.

Points with relevance smaller than this will be removed (m). Defaults to 0.01.

Definition at line 73 of file crossing_detector.h.

PlaceProfile used to compute the crossing.

Definition at line 62 of file crossing_detector.h.


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


crossing_detector
Author(s): Gaël Ecorchard , Karel Košnar , Vojtěch Vonásek
autogenerated on Thu Jun 6 2019 22:02:06