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

A Wrapper around Scan to allow for SLAM usage. More...

#include <SLAMScanWrapper.hpp>

Inheritance diagram for lvr2::SLAMScanWrapper:
Inheritance graph
[legend]

Public Member Functions

void addFrame (FrameUse use=FrameUse::UNUSED)
 Adds a new animation Frame with the current Pose. More...
 
const TransformddeltaPose () const
 Returns the difference between pose() and initialPose() More...
 
const std::pair< Transformd, FrameUse > & frame (size_t index) const
 Returns a Frame consisting of a Pose and a FrameUse. More...
 
size_t frameCount () const
 Returns the number of Frames generated. More...
 
Vector3d getPosition () const
 Get the Position of the Scan. Can also be obtained from pose() More...
 
const TransformdinitialPose () const
 Returns the initial Pose of the Scan. More...
 
ScanPtr innerScan ()
 Access to the Scan that this instance is wrapped around. More...
 
size_t numPoints () const
 Returns the number of Points in the Scan. More...
 
virtual Vector3d point (size_t index) const
 Returns the Point at the specified index in global Coordinates. More...
 
const Transformdpose () const
 Returns the current Pose of the Scan. More...
 
const Vector3frawPoint (size_t index) const
 Returns the Point at the specified index in local Coordinates. More...
 
void reduce (double voxelSize, int maxLeafSize)
 Reduces the Scan using Octree Reduction. More...
 
void setMaxDistance (double maxDistance)
 Reduces the Scan by removing all Points farther away than maxDistance to the origin. More...
 
void setMinDistance (double minDistance)
 Reduces the Scan by removing all Points closer than minDistance to the origin. More...
 
 SLAMScanWrapper (ScanPtr scan)
 Construct a new SLAMScanWrapper object as a Wrapper around the Scan. More...
 
virtual void transform (const Transformd &transform, bool writeFrame=true, FrameUse use=FrameUse::UPDATED)
 Applies a relative Transformation to the Scan. More...
 
void trim ()
 Reduces Memory usage by getting rid of Points removed with reduction Methods. More...
 
void writeFrames (std::string path) const
 Writes the Frames to the specified location. More...
 
virtual ~SLAMScanWrapper ()=default
 

Protected Attributes

Transformd m_deltaPose
 
std::vector< std::pair< Transformd, FrameUse > > m_frames
 
size_t m_numPoints
 
std::vector< Vector3fm_points
 
ScanPtr m_scan
 

Detailed Description

A Wrapper around Scan to allow for SLAM usage.

Definition at line 65 of file SLAMScanWrapper.hpp.

Constructor & Destructor Documentation

◆ SLAMScanWrapper()

lvr2::SLAMScanWrapper::SLAMScanWrapper ( ScanPtr  scan)

Construct a new SLAMScanWrapper object as a Wrapper around the Scan.

Parameters
scanThe Scan to wrap around

Definition at line 45 of file SLAMScanWrapper.cpp.

◆ ~SLAMScanWrapper()

virtual lvr2::SLAMScanWrapper::~SLAMScanWrapper ( )
virtualdefault

Member Function Documentation

◆ addFrame()

void lvr2::SLAMScanWrapper::addFrame ( FrameUse  use = FrameUse::UNUSED)

Adds a new animation Frame with the current Pose.

Parameters
useThe use of the Frame for coloring purposes

Definition at line 178 of file SLAMScanWrapper.cpp.

◆ deltaPose()

const Transformd & lvr2::SLAMScanWrapper::deltaPose ( ) const

Returns the difference between pose() and initialPose()

Returns
const Transformd& the delta Pose

Definition at line 163 of file SLAMScanWrapper.cpp.

◆ frame()

const std::pair< Transformd, FrameUse > & lvr2::SLAMScanWrapper::frame ( size_t  index) const

Returns a Frame consisting of a Pose and a FrameUse.

Parameters
indexthe index of the Frame
Returns
const std::pair<Transformd, FrameUse>& the Pose and FrameUse

Definition at line 188 of file SLAMScanWrapper.cpp.

◆ frameCount()

size_t lvr2::SLAMScanWrapper::frameCount ( ) const

Returns the number of Frames generated.

Returns
size_t the number of Frames

Definition at line 183 of file SLAMScanWrapper.cpp.

◆ getPosition()

Vector3d lvr2::SLAMScanWrapper::getPosition ( ) const

Get the Position of the Scan. Can also be obtained from pose()

Returns
Vector3d the Position

Definition at line 173 of file SLAMScanWrapper.cpp.

◆ initialPose()

const Transformd & lvr2::SLAMScanWrapper::initialPose ( ) const

Returns the initial Pose of the Scan.

Returns
const Transformd& the initial Pose

Definition at line 168 of file SLAMScanWrapper.cpp.

◆ innerScan()

ScanPtr lvr2::SLAMScanWrapper::innerScan ( )

Access to the Scan that this instance is wrapped around.

Returns
ScanPtr The Scan

Definition at line 73 of file SLAMScanWrapper.cpp.

◆ numPoints()

size_t lvr2::SLAMScanWrapper::numPoints ( ) const

Returns the number of Points in the Scan.

Returns
size_t the number of Points

Definition at line 153 of file SLAMScanWrapper.cpp.

◆ point()

Vector3d lvr2::SLAMScanWrapper::point ( size_t  index) const
virtual

Returns the Point at the specified index in global Coordinates.

Parameters
indexthe Index
Returns
Vector3d the Point in global Coordinates

Reimplemented in lvr2::Metascan.

Definition at line 141 of file SLAMScanWrapper.cpp.

◆ pose()

const Transformd & lvr2::SLAMScanWrapper::pose ( ) const

Returns the current Pose of the Scan.

Returns
const Transformd& the Pose

Definition at line 158 of file SLAMScanWrapper.cpp.

◆ rawPoint()

const Vector3f & lvr2::SLAMScanWrapper::rawPoint ( size_t  index) const

Returns the Point at the specified index in local Coordinates.

Parameters
indexthe Index
Returns
Vector3d the Point in local Coordinates

Definition at line 148 of file SLAMScanWrapper.cpp.

◆ reduce()

void lvr2::SLAMScanWrapper::reduce ( double  voxelSize,
int  maxLeafSize 
)

Reduces the Scan using Octree Reduction.

Does not change the amount of allocated Memory unless trim() is called

Parameters
voxelSize
maxLeafSize

Definition at line 89 of file SLAMScanWrapper.cpp.

◆ setMaxDistance()

void lvr2::SLAMScanWrapper::setMaxDistance ( double  maxDistance)

Reduces the Scan by removing all Points farther away than maxDistance to the origin.

Does not change the amount of allocated Memory unless trim() is called

Parameters
maxDistanceThe maximum Distance for a Point to have

Definition at line 115 of file SLAMScanWrapper.cpp.

◆ setMinDistance()

void lvr2::SLAMScanWrapper::setMinDistance ( double  minDistance)

Reduces the Scan by removing all Points closer than minDistance to the origin.

Does not change the amount of allocated Memory unless trim() is called

Parameters
minDistanceThe minimum Distance for a Point to have

Definition at line 95 of file SLAMScanWrapper.cpp.

◆ transform()

void lvr2::SLAMScanWrapper::transform ( const Transformd transform,
bool  writeFrame = true,
FrameUse  use = FrameUse::UPDATED 
)
virtual

Applies a relative Transformation to the Scan.

Parameters
transformThe Transformation
writeFrameweather or not to add a new animation Frame
useThe FrameUse if writeFrame is set to true

Reimplemented in lvr2::Metascan.

Definition at line 78 of file SLAMScanWrapper.cpp.

◆ trim()

void lvr2::SLAMScanWrapper::trim ( )

Reduces Memory usage by getting rid of Points removed with reduction Methods.

Definition at line 135 of file SLAMScanWrapper.cpp.

◆ writeFrames()

void lvr2::SLAMScanWrapper::writeFrames ( std::string  path) const

Writes the Frames to the specified location.

Parameters
pathThe path of the file to write to

Definition at line 193 of file SLAMScanWrapper.cpp.

Member Data Documentation

◆ m_deltaPose

Transformd lvr2::SLAMScanWrapper::m_deltaPose
protected

Definition at line 216 of file SLAMScanWrapper.hpp.

◆ m_frames

std::vector<std::pair<Transformd, FrameUse> > lvr2::SLAMScanWrapper::m_frames
protected

Definition at line 218 of file SLAMScanWrapper.hpp.

◆ m_numPoints

size_t lvr2::SLAMScanWrapper::m_numPoints
protected

Definition at line 214 of file SLAMScanWrapper.hpp.

◆ m_points

std::vector<Vector3f> lvr2::SLAMScanWrapper::m_points
protected

Definition at line 213 of file SLAMScanWrapper.hpp.

◆ m_scan

ScanPtr lvr2::SLAMScanWrapper::m_scan
protected

Definition at line 211 of file SLAMScanWrapper.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