Go to the documentation of this file.
34 #ifndef SLAMSCANWRAPPER_HPP_
35 #define SLAMSCANWRAPPER_HPP_
39 #include <Eigen/Dense>
110 void reduce(
double voxelSize,
int maxLeafSize);
201 const std::pair<Transformd, FrameUse>&
frame(
size_t index)
const;
218 std::vector<std::pair<Transformd, FrameUse>>
m_frames;
void setMaxDistance(double maxDistance)
Reduces the Scan by removing all Points farther away than maxDistance to the origin.
A Wrapper around Scan to allow for SLAM usage.
const Transformd & initialPose() const
Returns the initial Pose of the Scan.
void addFrame(FrameUse use=FrameUse::UNUSED)
Adds a new animation Frame with the current Pose.
const Transformd & deltaPose() const
Returns the difference between pose() and initialPose()
std::vector< Vector3f > m_points
@ GRAPHSLAM
The Scan was part of a GraphSLAM Iteration.
virtual void transform(const Transformd &transform, bool writeFrame=true, FrameUse use=FrameUse::UPDATED)
Applies a relative Transformation to the Scan.
@ UPDATED
The Scan changed since the last Frame.
Transform< double > Transformd
4x4 double precision transformation matrix
Vector3d getPosition() const
Get the Position of the Scan. Can also be obtained from pose()
@ UNUSED
The Scan did not change since the last Frame.
void writeFrame(const Transform< T > &transform, const boost::filesystem::path &framesOut)
Writes a Eigen transformation into a .frames file.
@ INVALID
The Scan has not been registered yet.
const std::pair< Transformd, FrameUse > & frame(size_t index) const
Returns a Frame consisting of a Pose and a FrameUse.
Eigen::Vector3f Vector3f
Eigen 3D vector, single precision.
const Vector3f & rawPoint(size_t index) const
Returns the Point at the specified index in local Coordinates.
SLAMScanWrapper(ScanPtr scan)
Construct a new SLAMScanWrapper object as a Wrapper around the Scan.
void setMinDistance(double minDistance)
Reduces the Scan by removing all Points closer than minDistance to the origin.
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
void writeFrames(std::string path) const
Writes the Frames to the specified location.
Eigen::Vector3d Vector3d
Eigen 3D vector, double precision.
FrameUse
Annotates the use of a Scan when creating an slam6D .frames file.
ScanPtr innerScan()
Access to the Scan that this instance is wrapped around.
size_t frameCount() const
Returns the number of Frames generated.
void reduce(double voxelSize, int maxLeafSize)
Reduces the Scan using Octree Reduction.
size_t numPoints() const
Returns the number of Points in the Scan.
virtual ~SLAMScanWrapper()=default
@ LOOPCLOSE
The Scan was part of a Loopclose Iteration.
void trim()
Reduces Memory usage by getting rid of Points removed with reduction Methods.
virtual Vector3d point(size_t index) const
Returns the Point at the specified index in global Coordinates.
const Transformd & pose() const
Returns the current Pose of the Scan.
std::vector< std::pair< Transformd, FrameUse > > m_frames
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