Classes | Public Types | Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | List of all members
AISNavigation::TreeOptimizer3 Struct Reference

Class that contains the core optimization algorithm. More...

#include <treeoptimizer3.hh>

Inheritance diagram for AISNavigation::TreeOptimizer3:
Inheritance graph
[legend]

Classes

struct  PM_t
 

Public Types

typedef std::vector< PosePoseVector
 
- Public Types inherited from AISNavigation::TreePoseGraph3
typedef Ops::CovarianceType CovarianceMatrix
 
typedef Ops::InformationType InformationMatrix
 
typedef Operations3D< double > Ops
 
typedef Ops::PoseType Pose
 
typedef Ops::RotationType Rotation
 
typedef Ops::TransformationType Transformation
 
typedef Ops::TranslationType Translation
 
- Public Types inherited from AISNavigation::TreePoseGraph< Operations3D< double > >
typedef Operations3D< double >::BaseType BaseType
 
typedef Operations3D< double >::CovarianceType Covariance
 
typedef EVComparator< Edge * >::CompareMode EdgeCompareMode
 
typedef std::list< Edge * > EdgeList
 
typedef std::map< Edge *, Edge * > EdgeMap
 
typedef std::multiset< Edge *, EVComparator< Edge * > > EdgeSet
 
typedef Operations3D< double >::InformationType Information
 
typedef Operations3D< double >::ParametersType Parameters
 
typedef Operations3D< double >::PoseType Pose
 
typedef Operations3D< double >::RotationType Rotation
 
typedef Operations3D< double >::TransformationType Transformation
 
typedef Operations3D< double >::TranslationType Translation
 
typedef std::map< int, Vertex * > VertexMap
 
typedef std::set< Vertex * > VertexSet
 

Public Member Functions

double angularError () const
 
double error (double *mre=0, double *mte=0, double *are=0, double *ate=0, TreePoseGraph3::EdgeSet *eset=0) const
 
double getRotGain () const
 
void initializeOnlineIterations ()
 
void initializeOnlineOptimization (EdgeCompareMode mode=EVComparator< Edge * >::CompareLevel)
 
void initializeOptimization (EdgeCompareMode mode=EVComparator< Edge * >::CompareLevel)
 
void initializeTreeParameters ()
 
void iterate (TreePoseGraph3::EdgeSet *eset=0, bool noPreconditioner=false)
 
double translationalError () const
 
 TreeOptimizer3 ()
 
virtual ~TreeOptimizer3 ()
 
- Public Member Functions inherited from AISNavigation::TreePoseGraph3
virtual void collapseEdge (Edge *e)
 
virtual void initializeFromParentEdge (Vertex *v)
 
void initializeOnTree ()
 
bool load (const char *filename, bool overrideCovariances=false, bool twoDimensions=false)
 
bool loadEquivalences (const char *filename)
 
void printDepth (std::ostream &os)
 
void printEdgesStat (std::ostream &os)
 
void printWidth (std::ostream &os)
 
void recomputeAllTransformations ()
 
virtual void revertEdgeInfo (Edge *e)
 
bool save (const char *filename)
 
bool saveGnuplot (const char *filename)
 
- Public Member Functions inherited from AISNavigation::TreePoseGraph< Operations3D< double > >
Edge * addEdge (Vertex *v1, Vertex *v2, const Transformation &t, const Information &i)
 
Edge * addIncrementalEdge (int id1, int id2, const Transformation &t, const Information &i)
 
Vertex * addVertex (int id, const Pose &pose)
 
EdgeSetaffectedEdges (Vertex *v)
 
EdgeSetaffectedEdges (VertexSet &vl)
 
bool buildMST (int id)
 
bool buildSimpleTree ()
 
void clear ()
 
void compressIndices ()
 
Edge * edge (int id1, int id2)
 
const Edge * edge (int id1, int id2) const
 
int maxIndex ()
 
int maxPathLength ()
 
Edge * removeEdge (Edge *eq)
 
Vertex * removeVertex (int id)
 
void revertEdge (Edge *e)
 
bool sanityCheck ()
 
EdgeSetsortEdges ()
 
int totalPathLength ()
 
void treeBreadthVisit (Action &act)
 
void treeDepthVisit (Action &act, Vertex *v)
 
 TreePoseGraph ()
 
Vertex * vertex (int id)
 
const Vertex * vertex (int id) const
 
virtual ~TreePoseGraph ()
 

Public Attributes

int iteration
 
bool restartOnDivergence
 
double rpFraction
 
- Public Attributes inherited from AISNavigation::TreePoseGraph3
int verboseLevel
 
- Public Attributes inherited from AISNavigation::TreePoseGraph< Operations3D< double > >
EdgeMap edges
 
Vertex * root
 
EdgeSetsortedEdges
 
VertexMap vertices
 

Protected Types

typedef std::vector< PM_tPMVector
 

Protected Member Functions

void computePreconditioner ()
 
double error (const Edge *e) const
 
Transformation getPose (Vertex *v, Vertex *top)
 
Rotation getRotation (Vertex *v, Vertex *top)
 
virtual bool isDone ()
 
double loopError (const Edge *e) const
 
double loopRotationalError (const Edge *e) const
 
virtual void onIterationFinished (int iteration)
 
virtual void onIterationStart (int i)
 
virtual void onRestartBegin ()
 
virtual void onRestartDone ()
 
virtual void onStepFinished (Edge *e)
 
virtual void onStepStart (Edge *e)
 
void propagateErrors (bool usePreconditioner=false)
 
void recomputeParameters (Vertex *v, Vertex *top)
 
void recomputeTransformations (Vertex *v, Vertex *top)
 
double rotationalError (const Edge *e) const
 
double translationalError (const Edge *e) const
 
double traslationalError (const Edge *e) const
 
- Protected Member Functions inherited from AISNavigation::TreePoseGraph< Operations3D< double > >
void fillEdgeInfo (Edge *e)
 
void fillEdgesInfo ()
 

Protected Attributes

double gamma [2]
 
PMVector M
 
std::vector< double > maxRotationalErrors
 
std::vector< double > maxTranslationalErrors
 
int mpl
 
double rotGain
 
double trasGain
 
- Protected Attributes inherited from AISNavigation::TreePoseGraph< Operations3D< double > >
EdgeCompareMode edgeCompareMode
 

Detailed Description

Class that contains the core optimization algorithm.

Definition at line 52 of file treeoptimizer3.hh.

Member Typedef Documentation

typedef std::vector< PM_t > AISNavigation::TreeOptimizer3::PMVector
protected

Definition at line 135 of file treeoptimizer3.hh.

Definition at line 53 of file treeoptimizer3.hh.

Constructor & Destructor Documentation

AISNavigation::TreeOptimizer3::TreeOptimizer3 ( )

Constructor

Definition at line 56 of file treeoptimizer3.cpp.

AISNavigation::TreeOptimizer3::~TreeOptimizer3 ( )
virtual

Destructor

Definition at line 64 of file treeoptimizer3.cpp.

Member Function Documentation

double AISNavigation::TreeOptimizer3::angularError ( ) const

Conmputes the gloabl error of the network

void AISNavigation::TreeOptimizer3::computePreconditioner ( )
protected

Definition at line 86 of file treeoptimizer3_iteration.cpp.

double AISNavigation::TreeOptimizer3::error ( double *  mre = 0,
double *  mte = 0,
double *  are = 0,
double *  ate = 0,
TreePoseGraph3::EdgeSet eset = 0 
) const

Conmputes the gloabl error of the network

Definition at line 249 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::error ( const Edge *  e) const
protected

Computes the error of the constraint/edge e

Definition at line 169 of file treeoptimizer3.cpp.

TreeOptimizer3::Transformation AISNavigation::TreeOptimizer3::getPose ( Vertex *  v,
Vertex *  top 
)
protected

Recomputes only the pose of the node v wrt. to an arbitraty parent (top) of v in the tree

Definition at line 145 of file treeoptimizer3.cpp.

TreeOptimizer3::Rotation AISNavigation::TreeOptimizer3::getRotation ( Vertex *  v,
Vertex *  top 
)
protected

Recomputes only the pose of the node v wrt. to an arbitraty parent (top) of v in the tree

Definition at line 156 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::getRotGain ( ) const
inline

Definition at line 85 of file treeoptimizer3.hh.

void AISNavigation::TreeOptimizer3::initializeOnlineIterations ( )

Definition at line 313 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::initializeOnlineOptimization ( EdgeCompareMode  mode = EVComparator<Edge*>::CompareLevel)

Definition at line 325 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::initializeOptimization ( EdgeCompareMode  mode = EVComparator<Edge*>::CompareLevel)

Initialization function

Definition at line 292 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::initializeTreeParameters ( )

Initialization function

Definition at line 67 of file treeoptimizer3.cpp.

bool AISNavigation::TreeOptimizer3::isDone ( )
protectedvirtual

callback for determining a termination condition, it can be used by an external thread for stopping the optimizer while performing an iteration.

Returns
true when the optimizer has to stop.

Definition at line 355 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::iterate ( TreePoseGraph3::EdgeSet eset = 0,
bool  noPreconditioner = false 
)

Performs one iteration of the algorithm

Definition at line 73 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::loopError ( const Edge *  e) const
protected

Computes the error of the constraint/edge e

Definition at line 214 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::loopRotationalError ( const Edge *  e) const
protected

Computes the rotational error of the constraint/edge e

Definition at line 231 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onIterationFinished ( int  iteration)
protectedvirtual

callback invoked after finishing a full iteration,

Parameters
ithe current iteration number

Definition at line 349 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onIterationStart ( int  i)
protectedvirtual

callback invoked before starting a full iteration,

Parameters
ithe current iteration number

Definition at line 345 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onRestartBegin ( )
protectedvirtual

callback invoked before a restart of the optimizer when the angular wraparound is detected

Definition at line 353 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onRestartDone ( )
protectedvirtual

callback invoked after a restart of the optimizer

Definition at line 354 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onStepFinished ( Edge *  e)
protectedvirtual

callback invoked after finishing the optimization of an individual constraint,

Parameters
ethe constraint optimized

Definition at line 341 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onStepStart ( Edge *  e)
protectedvirtual

callback invoked before starting the optimization of an individual constraint,

Parameters
ethe constraint being optimized

Definition at line 338 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::propagateErrors ( bool  usePreconditioner = false)
protected

Definition at line 128 of file treeoptimizer3_iteration.cpp.

void AISNavigation::TreeOptimizer3::recomputeParameters ( Vertex *  v,
Vertex *  top 
)
protected

Definition at line 137 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::recomputeTransformations ( Vertex *  v,
Vertex *  top 
)
protected

Definition at line 129 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::rotationalError ( const Edge *  e) const
protected

Conmputes the error of the constraint/edge e

Definition at line 200 of file treeoptimizer3.cpp.

double AISNavigation::TreeOptimizer3::translationalError ( ) const

Conmputes the gloabl error of the network

double AISNavigation::TreeOptimizer3::translationalError ( const Edge *  e) const
protected

Conmputes the error of the constraint/edge e

double AISNavigation::TreeOptimizer3::traslationalError ( const Edge *  e) const
protected

Definition at line 187 of file treeoptimizer3.cpp.

Member Data Documentation

double AISNavigation::TreeOptimizer3::gamma[2]
protected

Used to compute the learning rate lambda

Definition at line 128 of file treeoptimizer3.hh.

int AISNavigation::TreeOptimizer3::iteration

Iteration counter

Definition at line 88 of file treeoptimizer3.hh.

PMVector AISNavigation::TreeOptimizer3::M
protected

Definition at line 136 of file treeoptimizer3.hh.

std::vector<double> AISNavigation::TreeOptimizer3::maxRotationalErrors
protected

history of rhe maximum rotational errors*, used when adaptiveRestart is enabled

Definition at line 142 of file treeoptimizer3.hh.

std::vector<double> AISNavigation::TreeOptimizer3::maxTranslationalErrors
protected

history of rhe maximum rotational errors*, used when adaptiveRestart is enabled

Definition at line 145 of file treeoptimizer3.hh.

int AISNavigation::TreeOptimizer3::mpl
protected

cached maximum path length

Definition at line 139 of file treeoptimizer3.hh.

bool AISNavigation::TreeOptimizer3::restartOnDivergence

Definition at line 83 of file treeoptimizer3.hh.

double AISNavigation::TreeOptimizer3::rotGain
protected

Definition at line 146 of file treeoptimizer3.hh.

double AISNavigation::TreeOptimizer3::rpFraction

Definition at line 90 of file treeoptimizer3.hh.

double AISNavigation::TreeOptimizer3::trasGain
protected

Definition at line 146 of file treeoptimizer3.hh.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:42