Class that contains the core optimization algorithm.
More...
#include <treeoptimizer3.hh>
|
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 () |
|
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) |
|
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) |
|
EdgeSet * | affectedEdges (Vertex *v) |
|
EdgeSet * | affectedEdges (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 () |
|
EdgeSet * | sortEdges () |
|
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 () |
|
Class that contains the core optimization algorithm.
Definition at line 52 of file treeoptimizer3.hh.
◆ PMVector
◆ PoseVector
◆ TreeOptimizer3()
AISNavigation::TreeOptimizer3::TreeOptimizer3 |
( |
| ) |
|
◆ ~TreeOptimizer3()
AISNavigation::TreeOptimizer3::~TreeOptimizer3 |
( |
| ) |
|
|
virtual |
◆ angularError()
double AISNavigation::TreeOptimizer3::angularError |
( |
| ) |
const |
Conmputes the gloabl error of the network
◆ computePreconditioner()
void AISNavigation::TreeOptimizer3::computePreconditioner |
( |
| ) |
|
|
protected |
◆ error() [1/2]
double AISNavigation::TreeOptimizer3::error |
( |
double * |
mre = 0 , |
|
|
double * |
mte = 0 , |
|
|
double * |
are = 0 , |
|
|
double * |
ate = 0 , |
|
|
TreePoseGraph3::EdgeSet * |
eset = 0 |
|
) |
| const |
◆ error() [2/2]
double AISNavigation::TreeOptimizer3::error |
( |
const Edge * |
e | ) |
const |
|
protected |
◆ getPose()
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.
◆ getRotation()
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.
◆ getRotGain()
double AISNavigation::TreeOptimizer3::getRotGain |
( |
| ) |
const |
|
inline |
◆ initializeOnlineIterations()
void AISNavigation::TreeOptimizer3::initializeOnlineIterations |
( |
| ) |
|
◆ initializeOnlineOptimization()
◆ initializeOptimization()
◆ initializeTreeParameters()
void AISNavigation::TreeOptimizer3::initializeTreeParameters |
( |
| ) |
|
◆ isDone()
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.
◆ iterate()
◆ loopError()
double AISNavigation::TreeOptimizer3::loopError |
( |
const Edge * |
e | ) |
const |
|
protected |
◆ loopRotationalError()
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.
◆ onIterationFinished()
void AISNavigation::TreeOptimizer3::onIterationFinished |
( |
int |
iteration | ) |
|
|
protectedvirtual |
callback invoked after finishing a full iteration,
- Parameters
-
i | the current iteration number |
Definition at line 349 of file treeoptimizer3.cpp.
◆ onIterationStart()
void AISNavigation::TreeOptimizer3::onIterationStart |
( |
int |
i | ) |
|
|
protectedvirtual |
callback invoked before starting a full iteration,
- Parameters
-
i | the current iteration number |
Definition at line 345 of file treeoptimizer3.cpp.
◆ onRestartBegin()
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.
◆ onRestartDone()
void AISNavigation::TreeOptimizer3::onRestartDone |
( |
| ) |
|
|
protectedvirtual |
◆ onStepFinished()
void AISNavigation::TreeOptimizer3::onStepFinished |
( |
Edge * |
e | ) |
|
|
protectedvirtual |
callback invoked after finishing the optimization of an individual constraint,
- Parameters
-
e | the constraint optimized |
Definition at line 341 of file treeoptimizer3.cpp.
◆ onStepStart()
void AISNavigation::TreeOptimizer3::onStepStart |
( |
Edge * |
e | ) |
|
|
protectedvirtual |
callback invoked before starting the optimization of an individual constraint,
- Parameters
-
e | the constraint being optimized |
Definition at line 338 of file treeoptimizer3.cpp.
◆ propagateErrors()
void AISNavigation::TreeOptimizer3::propagateErrors |
( |
bool |
usePreconditioner = false | ) |
|
|
protected |
◆ recomputeParameters()
void AISNavigation::TreeOptimizer3::recomputeParameters |
( |
Vertex * |
v, |
|
|
Vertex * |
top |
|
) |
| |
|
protected |
◆ recomputeTransformations()
void AISNavigation::TreeOptimizer3::recomputeTransformations |
( |
Vertex * |
v, |
|
|
Vertex * |
top |
|
) |
| |
|
protected |
◆ rotationalError()
double AISNavigation::TreeOptimizer3::rotationalError |
( |
const Edge * |
e | ) |
const |
|
protected |
◆ translationalError() [1/2]
double AISNavigation::TreeOptimizer3::translationalError |
( |
| ) |
const |
Conmputes the gloabl error of the network
◆ translationalError() [2/2]
double AISNavigation::TreeOptimizer3::translationalError |
( |
const Edge * |
e | ) |
const |
|
protected |
Conmputes the error of the constraint/edge e
◆ traslationalError()
double AISNavigation::TreeOptimizer3::traslationalError |
( |
const Edge * |
e | ) |
const |
|
protected |
◆ gamma
double AISNavigation::TreeOptimizer3::gamma[2] |
|
protected |
◆ iteration
int AISNavigation::TreeOptimizer3::iteration |
PMVector AISNavigation::TreeOptimizer3::M |
|
protected |
◆ maxRotationalErrors
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.
◆ maxTranslationalErrors
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.
◆ mpl
int AISNavigation::TreeOptimizer3::mpl |
|
protected |
◆ restartOnDivergence
bool AISNavigation::TreeOptimizer3::restartOnDivergence |
◆ rotGain
double AISNavigation::TreeOptimizer3::rotGain |
|
protected |
◆ rpFraction
double AISNavigation::TreeOptimizer3::rpFraction |
◆ trasGain
double AISNavigation::TreeOptimizer3::trasGain |
|
protected |
The documentation for this struct was generated from the following files: