#include <G2oSolver.h>
Public Member Functions | |
virtual void | AddConstraint (karto::Edge< karto::LocalizedObjectPtr > *pEdge) |
virtual void | AddNode (karto::Vertex< karto::LocalizedObjectPtr > *pVertex) |
virtual void | Clear () |
virtual void | Compute () |
G2oSolver () | |
virtual const karto::ScanSolver::IdPoseVector & | GetCorrections () const |
virtual | ~G2oSolver () |
Private Attributes | |
karto::ScanSolver::IdPoseVector | mCorrections |
g2o::SparseOptimizer | mOptimizer |
Definition at line 8 of file G2oSolver.h.
Definition at line 21 of file G2oSolver.cpp.
G2oSolver::~G2oSolver | ( | ) | [virtual] |
Definition at line 30 of file G2oSolver.cpp.
void G2oSolver::AddConstraint | ( | karto::Edge< karto::LocalizedObjectPtr > * | ) | [virtual] |
Adds a constraint to the solver
Reimplemented from karto::ScanSolver.
Definition at line 94 of file G2oSolver.cpp.
void G2oSolver::AddNode | ( | karto::Vertex< karto::LocalizedObjectPtr > * | ) | [virtual] |
Adds a node to the solver
Reimplemented from karto::ScanSolver.
Definition at line 84 of file G2oSolver.cpp.
void G2oSolver::Clear | ( | ) | [virtual] |
Resets the solver
Reimplemented from karto::ScanSolver.
Definition at line 38 of file G2oSolver.cpp.
void G2oSolver::Compute | ( | ) | [virtual] |
const karto::ScanSolver::IdPoseVector & G2oSolver::GetCorrections | ( | ) | const [virtual] |
Gets corrected poses after optimization
Implements karto::ScanSolver.
Definition at line 139 of file G2oSolver.cpp.
Definition at line 24 of file G2oSolver.h.
g2o::SparseOptimizer G2oSolver::mOptimizer [private] |
Definition at line 25 of file G2oSolver.h.