Public Member Functions | Private Attributes | List of all members
teb_local_planner::HSignature3d Class Reference

The H-signature in three dimensions (here: x-y-t) defines an equivalence relation based on homology using theorems from electro magnetism. More...

#include <h_signature.h>

Inheritance diagram for teb_local_planner::HSignature3d:
Inheritance graph
[legend]

Public Member Functions

template<typename BidirIter , typename Fun >
void calculateHSignature (BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles, boost::optional< TimeDiffSequence::iterator > timediff_start, boost::optional< TimeDiffSequence::iterator > timediff_end)
 Calculate the H-Signature of a path. More...
 
 HSignature3d (const TebConfig &cfg)
 Constructor accepting a TebConfig. More...
 
virtual bool isEqual (const EquivalenceClass &other) const
 Check if two candidate classes are equivalent. More...
 
virtual bool isReasonable () const
 Check if the trajectory is non-looping around any obstacle. Values greater than 1 indicate a looping trajectory. More...
 
virtual bool isValid () const
 Check if the equivalence value is detected correctly. More...
 
const std::vector< double > & values () const
 Get the current h-signature (read-only) More...
 
- Public Member Functions inherited from teb_local_planner::EquivalenceClass
 EquivalenceClass ()
 Default constructor. More...
 
virtual ~EquivalenceClass ()
 virtual destructor More...
 

Private Attributes

const TebConfigcfg_
 
std::vector< double > hsignature3d_
 

Detailed Description

The H-signature in three dimensions (here: x-y-t) defines an equivalence relation based on homology using theorems from electro magnetism.

The H-Signature depends on the obstacle configuration and can be utilized to check whether two trajectores belong to the same homology class. Refer to:

Definition at line 254 of file h_signature.h.

Constructor & Destructor Documentation

teb_local_planner::HSignature3d::HSignature3d ( const TebConfig cfg)
inline

Constructor accepting a TebConfig.

Parameters
cfgTebConfig storing some user configuration options

Definition at line 261 of file h_signature.h.

Member Function Documentation

template<typename BidirIter , typename Fun >
void teb_local_planner::HSignature3d::calculateHSignature ( BidirIter  path_start,
BidirIter  path_end,
Fun  fun_cplx_point,
const ObstContainer obstacles,
boost::optional< TimeDiffSequence::iterator >  timediff_start,
boost::optional< TimeDiffSequence::iterator >  timediff_end 
)
inline

Calculate the H-Signature of a path.

The implemented function accepts generic path descriptions that are restricted to the following structure:
The path is composed of points T and is represented by a std::vector< T > or similar type (std::list, std::deque, ...).
Provide a unary function with the following signature std::complex< long double > (const T& point_type) that returns a complex value for the position (Re(*)=x, Im(*)=y).

T could also be a pointer type, if the passed function also accepts a const T* point_Type.

Parameters
path_startIterator to the first element in the path
path_endIterator to the last element in the path
obstaclesobstacle container
fun_cplx_pointfunction accepting the dereference iterator type and that returns the position as complex number.
Template Parameters
BidirIterBidirectional iterator type
Funfunction of the form std::complex< long double > (const T& point_type)

Definition at line 282 of file h_signature.h.

virtual bool teb_local_planner::HSignature3d::isEqual ( const EquivalenceClass other) const
inlinevirtual

Check if two candidate classes are equivalent.

If the absolute value of the H-Signature is equal or greater than 1, a loop (in x-y) around the obstacle is indicated. Positive H-Signature: Obstacle lies on the left hand side of the planned trajectory Negative H-Signature: Obstacle lies on the right hand side of the planned trajectory H-Signature equals zero: Obstacle lies in infinity, has no influence on trajectory

Parameters
otherThe other equivalence class to test with

Implements teb_local_planner::EquivalenceClass.

Definition at line 358 of file h_signature.h.

virtual bool teb_local_planner::HSignature3d::isReasonable ( ) const
inlinevirtual

Check if the trajectory is non-looping around any obstacle. Values greater than 1 indicate a looping trajectory.

Returns
Returns false, if the trajectory loops around an obstacle

Implements teb_local_planner::EquivalenceClass.

Definition at line 402 of file h_signature.h.

virtual bool teb_local_planner::HSignature3d::isValid ( ) const
inlinevirtual

Check if the equivalence value is detected correctly.

Returns
Returns false, if the equivalence class detection failed, e.g. if nan- or inf values occur.

Implements teb_local_planner::EquivalenceClass.

Definition at line 388 of file h_signature.h.

const std::vector<double>& teb_local_planner::HSignature3d::values ( ) const
inline

Get the current h-signature (read-only)

Returns
h-signature in complex-number format

Definition at line 416 of file h_signature.h.

Member Data Documentation

const TebConfig* teb_local_planner::HSignature3d::cfg_
private

Definition at line 419 of file h_signature.h.

std::vector<double> teb_local_planner::HSignature3d::hsignature3d_
private

Definition at line 420 of file h_signature.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10