Classes | Public Types | Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes
AISNavigation::TreeOptimizer3 Struct Reference

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

#include <treeoptimizer3.hh>

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

List of all members.

Classes

struct  PM_t

Public Types

typedef std::vector< PosePoseVector

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 Attributes

int iteration
bool restartOnDivergence
double rpFraction

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 Attributes

double gamma [2]
PMVector M
std::vector< double > maxRotationalErrors
std::vector< double > maxTranslationalErrors
int mpl
double rotGain
double trasGain

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

Constructor

Definition at line 56 of file treeoptimizer3.cpp.

Destructor

Definition at line 64 of file treeoptimizer3.cpp.


Member Function Documentation

Conmputes the gloabl error of the network

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.

Definition at line 313 of file treeoptimizer3.cpp.

Definition at line 325 of file treeoptimizer3.cpp.

Initialization function

Definition at line 292 of file treeoptimizer3.cpp.

Initialization function

Definition at line 67 of file treeoptimizer3.cpp.

bool AISNavigation::TreeOptimizer3::isDone ( ) [protected, virtual]

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) [protected, virtual]

callback invoked after finishing a full iteration,

Parameters:
i,:the current iteration number

Definition at line 349 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onIterationStart ( int  i) [protected, virtual]

callback invoked before starting a full iteration,

Parameters:
i,:the current iteration number

Definition at line 345 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onRestartBegin ( ) [protected, virtual]

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 ( ) [protected, virtual]

callback invoked after a restart of the optimizer

Definition at line 354 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onStepFinished ( Edge *  e) [protected, virtual]

callback invoked after finishing the optimization of an individual constraint,

Parameters:
e,:the constraint optimized

Definition at line 341 of file treeoptimizer3.cpp.

void AISNavigation::TreeOptimizer3::onStepStart ( Edge *  e) [protected, virtual]

callback invoked before starting the optimization of an individual constraint,

Parameters:
e,:the 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.

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.

Iteration counter

Definition at line 88 of file treeoptimizer3.hh.

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.

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

Definition at line 145 of file treeoptimizer3.hh.

cached maximum path length

Definition at line 139 of file treeoptimizer3.hh.

Definition at line 83 of file treeoptimizer3.hh.

Definition at line 146 of file treeoptimizer3.hh.

Definition at line 90 of file treeoptimizer3.hh.

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 Thu Jun 6 2019 21:59:39