Public Types | Public Member Functions | Friends | List of all members
karto::ScanSolver Class Referenceabstract

#include <Mapper.h>

Inheritance diagram for karto::ScanSolver:
Inheritance graph
[legend]

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 IdPoseVectorGetCorrections () const =0
 
virtual std::unordered_map< int, Eigen::Vector3d > * getGraph ()
 
virtual void GetNodeOrientation (const int &unique_id, double &pose)
 
virtual void ModifyNode (const int &unique_id, Eigen::Vector3d pose)
 
virtual void RemoveConstraint (kt_int32s, kt_int32s)
 
virtual void RemoveNode (kt_int32s)
 
virtual void Reset ()
 
 ScanSolver ()
 
template<class Archive >
void serialize (Archive &ar, const unsigned int version)
 
virtual ~ScanSolver ()
 

Friends

class boost::serialization::access
 

Detailed Description

Graph optimization algorithm

Definition at line 947 of file Mapper.h.

Member Typedef Documentation

◆ IdPoseVector

typedef std::vector<std::pair<kt_int32s, Pose2> > karto::ScanSolver::IdPoseVector

Vector of id-pose pairs

Definition at line 953 of file Mapper.h.

Constructor & Destructor Documentation

◆ ScanSolver()

karto::ScanSolver::ScanSolver ( )
inline

Default constructor

Definition at line 958 of file Mapper.h.

◆ ~ScanSolver()

virtual karto::ScanSolver::~ScanSolver ( )
inlinevirtual

Destructor

Definition at line 965 of file Mapper.h.

Member Function Documentation

◆ AddConstraint()

virtual void karto::ScanSolver::AddConstraint ( Edge< LocalizedRangeScan > *  )
inlinevirtual

Adds a constraint to the solver

Reimplemented in solver_plugins::GTSAMSolver, solver_plugins::G2OSolver, solver_plugins::SpaSolver, and solver_plugins::CeresSolver.

Definition at line 998 of file Mapper.h.

◆ AddNode()

virtual void karto::ScanSolver::AddNode ( Vertex< LocalizedRangeScan > *  )
inlinevirtual

Adds a node to the solver

Reimplemented in solver_plugins::GTSAMSolver, solver_plugins::G2OSolver, solver_plugins::SpaSolver, and solver_plugins::CeresSolver.

Definition at line 984 of file Mapper.h.

◆ Clear()

virtual void karto::ScanSolver::Clear ( )
inlinevirtual

Resets the solver

Reimplemented in solver_plugins::GTSAMSolver, solver_plugins::G2OSolver, solver_plugins::SpaSolver, and solver_plugins::CeresSolver.

Definition at line 1012 of file Mapper.h.

◆ Compute()

virtual void karto::ScanSolver::Compute ( )
pure virtual

◆ GetCorrections()

virtual const IdPoseVector& karto::ScanSolver::GetCorrections ( ) const
pure virtual

Get corrected poses after optimization

Returns
optimized poses

Implemented in solver_plugins::GTSAMSolver, solver_plugins::G2OSolver, solver_plugins::SpaSolver, and solver_plugins::CeresSolver.

◆ getGraph()

virtual std::unordered_map<int, Eigen::Vector3d>* karto::ScanSolver::getGraph ( )
inlinevirtual

Get graph stored

Reimplemented in solver_plugins::CeresSolver.

Definition at line 1026 of file Mapper.h.

◆ GetNodeOrientation()

virtual void karto::ScanSolver::GetNodeOrientation ( const int &  unique_id,
double &  pose 
)
inlinevirtual

Get node's yaw

Reimplemented in solver_plugins::CeresSolver.

Definition at line 1042 of file Mapper.h.

◆ ModifyNode()

virtual void karto::ScanSolver::ModifyNode ( const int &  unique_id,
Eigen::Vector3d  pose 
)
inlinevirtual

Modify a node's pose

Reimplemented in solver_plugins::CeresSolver.

Definition at line 1035 of file Mapper.h.

◆ RemoveConstraint()

virtual void karto::ScanSolver::RemoveConstraint ( kt_int32s  ,
kt_int32s   
)
inlinevirtual

Removes a constraint from the solver

Reimplemented in solver_plugins::CeresSolver.

Definition at line 1005 of file Mapper.h.

◆ RemoveNode()

virtual void karto::ScanSolver::RemoveNode ( kt_int32s  )
inlinevirtual

Removes a node from the solver

Reimplemented in solver_plugins::CeresSolver.

Definition at line 991 of file Mapper.h.

◆ Reset()

virtual void karto::ScanSolver::Reset ( )
inlinevirtual

Resets the solver for reinitialization

Reimplemented in solver_plugins::CeresSolver.

Definition at line 1019 of file Mapper.h.

◆ serialize()

template<class Archive >
void karto::ScanSolver::serialize ( Archive &  ar,
const unsigned int  version 
)
inline

Definition at line 1049 of file Mapper.h.

Friends And Related Function Documentation

◆ boost::serialization::access

friend class boost::serialization::access
friend

Definition at line 1045 of file Mapper.h.


The documentation for this class was generated from the following file:


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56