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

A class to run SLAM on Scans. More...

#include <SLAMAlign.hpp>

Public Member Functions

void addScan (const ScanPtr &scan, bool match=false)
 Adds a new Scan to the SLAM instance. More...
 
void addScan (const SLAMScanPtr &scan, bool match=false)
 Adds a new Scan to the SLAM instance. More...
 
void finish ()
 Indicates that no new Scans will be added. More...
 
void match ()
 Executes SLAM on all current Scans. More...
 
SLAMOptionsoptions ()
 Returns a reference to the internal SLAMOptions struct. More...
 
const SLAMOptionsoptions () const
 Returns a reference to the internal SLAMOptions struct. More...
 
SLAMScanPtr scan (size_t index) const
 Returns a shared_ptr to a Scan. More...
 
void setOptions (const SLAMOptions &options)
 Sets the SLAMOptions struct to the parameter. More...
 
 SLAMAlign (const SLAMOptions &options, const std::vector< SLAMScanPtr > &scans, std::vector< bool > new_scans=std::vector< bool >())
 Creates a new SLAMAlign instance with the given Options and Scans. More...
 
 SLAMAlign (const SLAMOptions &options=SLAMOptions(), std::vector< bool > new_scans=std::vector< bool >())
 Creates a new SLAMAlign instance with the given Options. More...
 
virtual ~SLAMAlign ()=default
 

Protected Member Functions

void applyTransform (SLAMScanPtr scan, const Matrix4d &transform)
 Applies the Transformation to the specified Scan and adds a frame to all other Scans. More...
 
void checkLoopClose (size_t last)
 Checks for and executes any loopcloses that occur. More...
 
void checkLoopCloseOtherOrder (size_t last)
 checkLoopClose(size_t last) if the m_icp_graph is in a spezial order More...
 
void createIcpGraph ()
 Create m_icp_graph which defined the order of registrations. More...
 
void graphSLAM (size_t last)
 Executes GraphSLAM up to and including the specified last Scan. More...
 
void loopClose (size_t first, size_t last)
 Closes a simple Loop between first and last. More...
 
void reduceScan (const SLAMScanPtr &scan)
 Applies all reductions to the Scan. More...
 

Protected Attributes

bool m_foundLoop
 
GraphSLAM m_graph
 
std::vector< std::pair< int, int > > m_icp_graph
 
int m_loopIndexCount
 
SLAMScanPtr m_metascan
 
std::vector< bool > m_new_scans
 
SLAMOptions m_options
 
std::vector< SLAMScanPtrm_scans
 

Detailed Description

A class to run SLAM on Scans.

Definition at line 48 of file SLAMAlign.hpp.

Constructor & Destructor Documentation

◆ SLAMAlign() [1/2]

lvr2::SLAMAlign::SLAMAlign ( const SLAMOptions options,
const std::vector< SLAMScanPtr > &  scans,
std::vector< bool >  new_scans = std::vector< bool >() 
)

Creates a new SLAMAlign instance with the given Options and Scans.

This does not yet register the Scans, it only applies reduction options if specified

Parameters
optionsThe Options to use
scansThe Scans to start with

◆ SLAMAlign() [2/2]

lvr2::SLAMAlign::SLAMAlign ( const SLAMOptions options = SLAMOptions(),
std::vector< bool >  new_scans = std::vector<bool>() 
)

Creates a new SLAMAlign instance with the given Options.

Parameters
optionsThe Options to use

Definition at line 57 of file SLAMAlign.cpp.

◆ ~SLAMAlign()

virtual lvr2::SLAMAlign::~SLAMAlign ( )
virtualdefault

Member Function Documentation

◆ addScan() [1/2]

void lvr2::SLAMAlign::addScan ( const ScanPtr scan,
bool  match = false 
)

Adds a new Scan to the SLAM instance.

This method will apply any reduction options that are specified

Parameters
scanThe new Scan
matchtrue: Immediately call match() with the new Scan added

Definition at line 88 of file SLAMAlign.cpp.

◆ addScan() [2/2]

void lvr2::SLAMAlign::addScan ( const SLAMScanPtr scan,
bool  match = false 
)

Adds a new Scan to the SLAM instance.

This method will apply any reduction options that are specified

Parameters
scanThe new Scan
matchtrue: Immediately call match() with the new Scan added

Definition at line 77 of file SLAMAlign.cpp.

◆ applyTransform()

void lvr2::SLAMAlign::applyTransform ( SLAMScanPtr  scan,
const Matrix4d transform 
)
protected

Applies the Transformation to the specified Scan and adds a frame to all other Scans.

Definition at line 207 of file SLAMAlign.cpp.

◆ checkLoopClose()

void lvr2::SLAMAlign::checkLoopClose ( size_t  last)
protected

Checks for and executes any loopcloses that occur.

Definition at line 269 of file SLAMAlign.cpp.

◆ checkLoopCloseOtherOrder()

void lvr2::SLAMAlign::checkLoopCloseOtherOrder ( size_t  last)
protected

checkLoopClose(size_t last) if the m_icp_graph is in a spezial order

same as checkLoopClose(size_t last) but if the m_icp_graph is in a spezial order

Same as checkLoopClose(size_t last) but if the m_icp_graph is in a spezial order.

Definition at line 228 of file SLAMAlign.cpp.

◆ createIcpGraph()

void lvr2::SLAMAlign::createIcpGraph ( )
protected

Create m_icp_graph which defined the order of registrations.

Create m_icp_graph which defined the order of registrations. The first scan is regarded as registered. Then the scan that is closest to one of the already matched scans is always added. Therefore the scan centers were compared using Euclidean distance.

Definition at line 385 of file SLAMAlign.cpp.

◆ finish()

void lvr2::SLAMAlign::finish ( )

Indicates that no new Scans will be added.

This method ensures that all Scans are properly registered, including any Loopclosing

Definition at line 369 of file SLAMAlign.cpp.

◆ graphSLAM()

void lvr2::SLAMAlign::graphSLAM ( size_t  last)
protected

Executes GraphSLAM up to and including the specified last Scan.

Definition at line 364 of file SLAMAlign.cpp.

◆ loopClose()

void lvr2::SLAMAlign::loopClose ( size_t  first,
size_t  last 
)
protected

Closes a simple Loop between first and last.

Definition at line 312 of file SLAMAlign.cpp.

◆ match()

void lvr2::SLAMAlign::match ( )

Executes SLAM on all current Scans.

This methods registers any new Scans added since the last call to match() (or the creation of this instance) using Scanmatching and Loopclosing, as specified by the SLAMOptions.

Calling this method several times without adding any new Scans has no additional effect after the first call.

Definition at line 125 of file SLAMAlign.cpp.

◆ options() [1/2]

const SLAMOptions & lvr2::SLAMAlign::options ( )

Returns a reference to the internal SLAMOptions struct.

This can be used to make changes to specific values within the SLAMOptions without replacing the entire struct.

Note that changing options on an active SLAMAlign instance with previously added / matched Scans can cause Undefined Behaviour.

Definition at line 67 of file SLAMAlign.cpp.

◆ options() [2/2]

const SLAMOptions& lvr2::SLAMAlign::options ( ) const

Returns a reference to the internal SLAMOptions struct.

◆ reduceScan()

void lvr2::SLAMAlign::reduceScan ( const SLAMScanPtr scan)
protected

Applies all reductions to the Scan.

Definition at line 98 of file SLAMAlign.cpp.

◆ scan()

SLAMScanPtr lvr2::SLAMAlign::scan ( size_t  index) const

Returns a shared_ptr to a Scan.

Parameters
indexThe index of the Scan

Definition at line 93 of file SLAMAlign.cpp.

◆ setOptions()

void lvr2::SLAMAlign::setOptions ( const SLAMOptions options)

Sets the SLAMOptions struct to the parameter.

Note that changing options on an active SLAMAlign instance with previously added / matched Scans can cause Undefined Behaviour.

Parameters
optionsThe new options

Definition at line 62 of file SLAMAlign.cpp.

Member Data Documentation

◆ m_foundLoop

bool lvr2::SLAMAlign::m_foundLoop
protected

Definition at line 184 of file SLAMAlign.hpp.

◆ m_graph

GraphSLAM lvr2::SLAMAlign::m_graph
protected

Definition at line 183 of file SLAMAlign.hpp.

◆ m_icp_graph

std::vector<std::pair<int, int> > lvr2::SLAMAlign::m_icp_graph
protected

Definition at line 189 of file SLAMAlign.hpp.

◆ m_loopIndexCount

int lvr2::SLAMAlign::m_loopIndexCount
protected

Definition at line 185 of file SLAMAlign.hpp.

◆ m_metascan

SLAMScanPtr lvr2::SLAMAlign::m_metascan
protected

Definition at line 181 of file SLAMAlign.hpp.

◆ m_new_scans

std::vector<bool> lvr2::SLAMAlign::m_new_scans
protected

Definition at line 187 of file SLAMAlign.hpp.

◆ m_options

SLAMOptions lvr2::SLAMAlign::m_options
protected

Definition at line 177 of file SLAMAlign.hpp.

◆ m_scans

std::vector<SLAMScanPtr> lvr2::SLAMAlign::m_scans
protected

Definition at line 179 of file SLAMAlign.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