#include <Mapper.h>
Public Types | |
typedef std::vector< std::pair < kt_int32s, Pose2 > > | IdPoseVector |
Public Member Functions | |
virtual void | AddConstraint (Edge< LocalizedRangeScan > *) |
virtual void | AddNode (Vertex< LocalizedRangeScan > *) |
virtual void | Clear () |
virtual void | Compute ()=0 |
virtual const IdPoseVector & | GetCorrections () const =0 |
virtual void | RemoveConstraint (kt_int32s, kt_int32s) |
virtual void | RemoveNode (kt_int32s) |
ScanSolver () | |
virtual | ~ScanSolver () |
typedef std::vector<std::pair<kt_int32s, Pose2> > karto::ScanSolver::IdPoseVector |
karto::ScanSolver::ScanSolver | ( | ) | [inline] |
virtual karto::ScanSolver::~ScanSolver | ( | ) | [inline, virtual] |
virtual void karto::ScanSolver::AddConstraint | ( | Edge< LocalizedRangeScan > * | ) | [inline, virtual] |
virtual void karto::ScanSolver::AddNode | ( | Vertex< LocalizedRangeScan > * | ) | [inline, virtual] |
virtual void karto::ScanSolver::Clear | ( | ) | [inline, virtual] |
virtual void karto::ScanSolver::Compute | ( | ) | [pure virtual] |
Solve!
Implemented in SpaSolver.
virtual const IdPoseVector& karto::ScanSolver::GetCorrections | ( | ) | const [pure virtual] |
virtual void karto::ScanSolver::RemoveConstraint | ( | kt_int32s | , |
kt_int32s | |||
) | [inline, virtual] |
virtual void karto::ScanSolver::RemoveNode | ( | kt_int32s | ) | [inline, virtual] |