Go to the documentation of this file.
35 #ifndef SLAMALIGN_HPP_
36 #define SLAMALIGN_HPP_
std::vector< SLAMScanPtr > m_scans
void reduceScan(const SLAMScanPtr &scan)
Applies all reductions to the Scan.
void applyTransform(SLAMScanPtr scan, const Matrix4d &transform)
Applies the Transformation to the specified Scan and adds a frame to all other Scans.
std::vector< bool > m_new_scans
virtual ~SLAMAlign()=default
SLAMScanPtr scan(size_t index) const
Returns a shared_ptr to a Scan.
Eigen::Matrix4d Matrix4d
Eigen 4x4 matrix, double precision.
void setOptions(const SLAMOptions &options)
Sets the SLAMOptions struct to the parameter.
SLAMOptions & options()
Returns a reference to the internal SLAMOptions struct.
void loopClose(size_t first, size_t last)
Closes a simple Loop between first and last.
void checkLoopClose(size_t last)
Checks for and executes any loopcloses that occur.
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
void match()
Executes SLAM on all current Scans.
void checkLoopCloseOtherOrder(size_t last)
checkLoopClose(size_t last) if the m_icp_graph is in a spezial order
void graphSLAM(size_t last)
Executes GraphSLAM up to and including the specified last Scan.
void createIcpGraph()
Create m_icp_graph which defined the order of registrations.
A class to run SLAM on Scans.
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.
void finish()
Indicates that no new Scans will be added.
A struct to configure SLAMAlign.
std::vector< std::pair< int, int > > m_icp_graph
void addScan(const SLAMScanPtr &scan, bool match=false)
Adds a new Scan to the SLAM instance.
Wrapper class for running GraphSLAM on Scans.
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
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:25