Public Member Functions | Private Attributes | List of all members
solver_plugins::G2OSolver Class Reference

Wrapper for G2O to interface with Open Karto. More...

#include <g2o_solver.hpp>

Inheritance diagram for solver_plugins::G2OSolver:
Inheritance graph
[legend]

Public Member Functions

virtual void AddConstraint (karto::Edge< karto::LocalizedRangeScan > *pEdge)
 Add an edge constraint to pose-graph. More...
 
virtual void AddNode (karto::Vertex< karto::LocalizedRangeScan > *pVertex)
 Add a node to pose-graph. More...
 
virtual void Clear ()
 Clear the vector of corrections. More...
 
virtual void Compute ()
 Solve the SLAM back-end. More...
 
 G2OSolver ()
 
virtual const karto::ScanSolver::IdPoseVectorGetCorrections () const
 Get the vector of corrections. More...
 
void getGraph (std::vector< Eigen::Vector2d > &nodes)
 Get the pose-graph. More...
 
virtual void ModifyNode (const int &unique_id, const Eigen::Vector3d &pose)
 
void useRobustKernel (bool flag)
 Use robust kernel in back-end. More...
 
virtual ~G2OSolver ()
 
- Public Member Functions inherited from karto::ScanSolver
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 ()
 

Private Attributes

karto::ScanSolver::IdPoseVector corrections_
 
int latestNodeID_
 
g2o::SparseOptimizer optimizer_
 
bool useRobustKernel_
 

Additional Inherited Members

- Public Types inherited from karto::ScanSolver
typedef std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
 

Detailed Description

Wrapper for G2O to interface with Open Karto.

Definition at line 21 of file g2o_solver.hpp.

Constructor & Destructor Documentation

◆ G2OSolver()

solver_plugins::G2OSolver::G2OSolver ( )

Definition at line 33 of file g2o_solver.cpp.

◆ ~G2OSolver()

solver_plugins::G2OSolver::~G2OSolver ( )
virtual

Definition at line 49 of file g2o_solver.cpp.

Member Function Documentation

◆ AddConstraint()

void solver_plugins::G2OSolver::AddConstraint ( karto::Edge< karto::LocalizedRangeScan > *  pEdge)
virtual

Add an edge constraint to pose-graph.

Adds a relative pose measurement constraint between two poses in the graph

Parameters
pEdge[description]

Reimplemented from karto::ScanSolver.

Definition at line 135 of file g2o_solver.cpp.

◆ AddNode()

void solver_plugins::G2OSolver::AddNode ( karto::Vertex< karto::LocalizedRangeScan > *  pVertex)
virtual

Add a node to pose-graph.

Add a node which is a robot pose to the pose-graph

Parameters
pVertexthe node to be added in

Reimplemented from karto::ScanSolver.

Definition at line 119 of file g2o_solver.cpp.

◆ Clear()

void solver_plugins::G2OSolver::Clear ( )
virtual

Clear the vector of corrections.

Empty out previously computed corrections

Reimplemented from karto::ScanSolver.

Definition at line 59 of file g2o_solver.cpp.

◆ Compute()

void solver_plugins::G2OSolver::Compute ( )
virtual

Solve the SLAM back-end.

Calls G2O to solve the SLAM back-end

Implements karto::ScanSolver.

Definition at line 71 of file g2o_solver.cpp.

◆ GetCorrections()

const karto::ScanSolver::IdPoseVector & solver_plugins::G2OSolver::GetCorrections ( ) const
virtual

Get the vector of corrections.

Get the vector of corrections

Returns
Vector with corrected poses

Implements karto::ScanSolver.

Definition at line 65 of file g2o_solver.cpp.

◆ getGraph()

void solver_plugins::G2OSolver::getGraph ( std::vector< Eigen::Vector2d > &  nodes)

Get the pose-graph.

Get the underlying graph from g2o, return the graph of constraints

Parameters
gthe graph

Definition at line 192 of file g2o_solver.cpp.

◆ ModifyNode()

virtual void solver_plugins::G2OSolver::ModifyNode ( const int &  unique_id,
const Eigen::Vector3d &  pose 
)
virtual

◆ useRobustKernel()

void solver_plugins::G2OSolver::useRobustKernel ( bool  flag)
inline

Use robust kernel in back-end.

Uses Dynamic Covariance scaling kernel in back-end

Parameters
flagvariable, if true robust kernel will be used

Definition at line 80 of file g2o_solver.hpp.

Member Data Documentation

◆ corrections_

karto::ScanSolver::IdPoseVector solver_plugins::G2OSolver::corrections_
private

Definition at line 89 of file g2o_solver.hpp.

◆ latestNodeID_

int solver_plugins::G2OSolver::latestNodeID_
private

Definition at line 93 of file g2o_solver.hpp.

◆ optimizer_

g2o::SparseOptimizer solver_plugins::G2OSolver::optimizer_
private

Definition at line 91 of file g2o_solver.hpp.

◆ useRobustKernel_

bool solver_plugins::G2OSolver::useRobustKernel_
private

Definition at line 95 of file g2o_solver.hpp.


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


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:50