Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
lvr2::GraphSLAM Class Reference

Wrapper class for running GraphSLAM on Scans. More...

#include <GraphSLAM.hpp>

Public Types

using Graph = std::vector< std::pair< int, int > >
 
using GraphMatrix = Eigen::SparseMatrix< double >
 
using GraphVector = Eigen::VectorXd
 

Public Member Functions

void doGraphSLAM (const std::vector< SLAMScanPtr > &scans, size_t last, const std::vector< bool > &new_scans=std::vector< bool >()) const
 runs the GraphSLAM algorithm More...
 
 GraphSLAM (const SLAMOptions *options)
 
virtual ~GraphSLAM ()=default
 

Protected Member Functions

void createGraph (const std::vector< SLAMScanPtr > &scans, size_t last, Graph &graph) const
 Creates a graph. An edge between nodes(scans) means posible overlap. More...
 
void eulerCovariance (KDTreePtr tree, SLAMScanPtr scan, Matrix6d &outMat, Vector6d &outVec) const
 
void fillEquation (const std::vector< SLAMScanPtr > &scans, const Graph &graph, GraphMatrix &mat, GraphVector &vec) const
 A function to fill the linear system mat * x = vec. More...
 

Protected Attributes

const SLAMOptionsm_options
 

Detailed Description

Wrapper class for running GraphSLAM on Scans.

Definition at line 61 of file GraphSLAM.hpp.

Member Typedef Documentation

◆ Graph

using lvr2::GraphSLAM::Graph = std::vector<std::pair<int, int> >

Definition at line 67 of file GraphSLAM.hpp.

◆ GraphMatrix

using lvr2::GraphSLAM::GraphMatrix = Eigen::SparseMatrix<double>

Definition at line 65 of file GraphSLAM.hpp.

◆ GraphVector

using lvr2::GraphSLAM::GraphVector = Eigen::VectorXd

Definition at line 66 of file GraphSLAM.hpp.

Constructor & Destructor Documentation

◆ GraphSLAM()

lvr2::GraphSLAM::GraphSLAM ( const SLAMOptions options)

Definition at line 117 of file GraphSLAM.cpp.

◆ ~GraphSLAM()

virtual lvr2::GraphSLAM::~GraphSLAM ( )
virtualdefault

Member Function Documentation

◆ createGraph()

void lvr2::GraphSLAM::createGraph ( const std::vector< SLAMScanPtr > &  scans,
size_t  last,
Graph graph 
) const
protected

Creates a graph. An edge between nodes(scans) means posible overlap.

Parameters
scansreference to a vector containing the SlamScanPtr
lastnumber of the last considered scan
graphOutputs the created graph

Definition at line 243 of file GraphSLAM.cpp.

◆ doGraphSLAM()

void lvr2::GraphSLAM::doGraphSLAM ( const std::vector< SLAMScanPtr > &  scans,
size_t  last,
const std::vector< bool > &  new_scans = std::vector<bool>() 
) const

runs the GraphSLAM algorithm

Parameters
scansThe scans to work on
lastThe index of the last Scan to consider. scans may be longer, but anything after last will be ignored

Definition at line 122 of file GraphSLAM.cpp.

◆ eulerCovariance()

void lvr2::GraphSLAM::eulerCovariance ( KDTreePtr  tree,
SLAMScanPtr  scan,
Matrix6d outMat,
Vector6d outVec 
) const
protected

Definition at line 392 of file GraphSLAM.cpp.

◆ fillEquation()

void lvr2::GraphSLAM::fillEquation ( const std::vector< SLAMScanPtr > &  scans,
const Graph graph,
GraphMatrix mat,
GraphVector vec 
) const
protected

A function to fill the linear system mat * x = vec.

Parameters
scansreference to a vector containing the SlamScanPtr
graphthe graph created in the createGraph function
matOutputs the GraphMatrix
vecOutputs the GraphVector

Definition at line 266 of file GraphSLAM.cpp.

Member Data Documentation

◆ m_options

const SLAMOptions* lvr2::GraphSLAM::m_options
protected

Definition at line 102 of file GraphSLAM.hpp.


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


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:27