A Wrapper around Scan to allow for SLAM usage. More...
#include <SLAMScanWrapper.hpp>
Public Member Functions | |
void | addFrame (FrameUse use=FrameUse::UNUSED) |
Adds a new animation Frame with the current Pose. More... | |
const Transformd & | deltaPose () 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 Transformd & | initialPose () 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 Transformd & | pose () const |
Returns the current Pose of the Scan. More... | |
const Vector3f & | rawPoint (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< Vector3f > | m_points |
ScanPtr | m_scan |
A Wrapper around Scan to allow for SLAM usage.
Definition at line 65 of file SLAMScanWrapper.hpp.
lvr2::SLAMScanWrapper::SLAMScanWrapper | ( | ScanPtr | scan | ) |
Construct a new SLAMScanWrapper object as a Wrapper around the Scan.
scan | The Scan to wrap around |
Definition at line 45 of file SLAMScanWrapper.cpp.
|
virtualdefault |
void lvr2::SLAMScanWrapper::addFrame | ( | FrameUse | use = FrameUse::UNUSED | ) |
Adds a new animation Frame with the current Pose.
use | The use of the Frame for coloring purposes |
Definition at line 178 of file SLAMScanWrapper.cpp.
const Transformd & lvr2::SLAMScanWrapper::deltaPose | ( | ) | const |
Returns the difference between pose() and initialPose()
Definition at line 163 of file SLAMScanWrapper.cpp.
const std::pair< Transformd, FrameUse > & lvr2::SLAMScanWrapper::frame | ( | size_t | index | ) | const |
Returns a Frame consisting of a Pose and a FrameUse.
index | the index of the Frame |
Definition at line 188 of file SLAMScanWrapper.cpp.
size_t lvr2::SLAMScanWrapper::frameCount | ( | ) | const |
Returns the number of Frames generated.
Definition at line 183 of file SLAMScanWrapper.cpp.
Vector3d lvr2::SLAMScanWrapper::getPosition | ( | ) | const |
Get the Position of the Scan. Can also be obtained from pose()
Definition at line 173 of file SLAMScanWrapper.cpp.
const Transformd & lvr2::SLAMScanWrapper::initialPose | ( | ) | const |
Returns the initial Pose of the Scan.
Definition at line 168 of file SLAMScanWrapper.cpp.
ScanPtr lvr2::SLAMScanWrapper::innerScan | ( | ) |
Access to the Scan that this instance is wrapped around.
Definition at line 73 of file SLAMScanWrapper.cpp.
size_t lvr2::SLAMScanWrapper::numPoints | ( | ) | const |
Returns the number of Points in the Scan.
Definition at line 153 of file SLAMScanWrapper.cpp.
|
virtual |
Returns the Point at the specified index in global Coordinates.
index | the Index |
Reimplemented in lvr2::Metascan.
Definition at line 141 of file SLAMScanWrapper.cpp.
const Transformd & lvr2::SLAMScanWrapper::pose | ( | ) | const |
Returns the current Pose of the Scan.
Definition at line 158 of file SLAMScanWrapper.cpp.
const Vector3f & lvr2::SLAMScanWrapper::rawPoint | ( | size_t | index | ) | const |
Returns the Point at the specified index in local Coordinates.
index | the Index |
Definition at line 148 of file SLAMScanWrapper.cpp.
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
voxelSize | |
maxLeafSize |
Definition at line 89 of file SLAMScanWrapper.cpp.
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
maxDistance | The maximum Distance for a Point to have |
Definition at line 115 of file SLAMScanWrapper.cpp.
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
minDistance | The minimum Distance for a Point to have |
Definition at line 95 of file SLAMScanWrapper.cpp.
|
virtual |
Applies a relative Transformation to the Scan.
transform | The Transformation |
writeFrame | weather or not to add a new animation Frame |
use | The FrameUse if writeFrame is set to true |
Reimplemented in lvr2::Metascan.
Definition at line 78 of file SLAMScanWrapper.cpp.
void lvr2::SLAMScanWrapper::trim | ( | ) |
Reduces Memory usage by getting rid of Points removed with reduction Methods.
Definition at line 135 of file SLAMScanWrapper.cpp.
void lvr2::SLAMScanWrapper::writeFrames | ( | std::string | path | ) | const |
Writes the Frames to the specified location.
path | The path of the file to write to |
Definition at line 193 of file SLAMScanWrapper.cpp.
|
protected |
Definition at line 216 of file SLAMScanWrapper.hpp.
|
protected |
Definition at line 218 of file SLAMScanWrapper.hpp.
|
protected |
Definition at line 214 of file SLAMScanWrapper.hpp.
|
protected |
Definition at line 213 of file SLAMScanWrapper.hpp.
|
protected |
Definition at line 211 of file SLAMScanWrapper.hpp.