SLAMScanWrapper.hpp
Go to the documentation of this file.
1 
34 #ifndef SLAMSCANWRAPPER_HPP_
35 #define SLAMSCANWRAPPER_HPP_
36 
37 #include "lvr2/types/ScanTypes.hpp"
38 
39 #include <Eigen/Dense>
40 #include <vector>
41 
42 namespace lvr2
43 {
44 
48 enum class FrameUse
49 {
51  INVALID = 0,
53  UPDATED = 1,
55  UNUSED = 2,
57  GRAPHSLAM = 3,
59  LOOPCLOSE = 4,
60 };
61 
66 {
67 public:
74 
75  virtual ~SLAMScanWrapper() = default;
76 
83 
84 
92  virtual void transform(const Transformd& transform, bool writeFrame = true, FrameUse use = FrameUse::UPDATED);
93 
100 
101 
110  void reduce(double voxelSize, int maxLeafSize);
111 
119  void setMinDistance(double minDistance);
120 
128  void setMaxDistance(double maxDistance);
129 
133  void trim();
134 
135 
142  virtual Vector3d point(size_t index) const;
143 
150  const Vector3f& rawPoint(size_t index) const;
151 
157  size_t numPoints() const;
158 
159 
165  const Transformd& pose() const;
166 
172  const Transformd& deltaPose() const;
173 
179  const Transformd& initialPose() const;
180 
186  Vector3d getPosition() const;
187 
193  size_t frameCount() const;
194 
201  const std::pair<Transformd, FrameUse>& frame(size_t index) const;
202 
208  void writeFrames(std::string path) const;
209 
210 protected:
212 
213  std::vector<Vector3f> m_points;
214  size_t m_numPoints;
215 
217 
218  std::vector<std::pair<Transformd, FrameUse>> m_frames;
219 };
220 
221 using SLAMScanPtr = std::shared_ptr<SLAMScanWrapper>;
222 
223 } /* namespace lvr2 */
224 
225 #endif /* SLAMSCANWRAPPER_HPP_ */
lvr2::SLAMScanWrapper::setMaxDistance
void setMaxDistance(double maxDistance)
Reduces the Scan by removing all Points farther away than maxDistance to the origin.
Definition: SLAMScanWrapper.cpp:115
lvr2::SLAMScanWrapper
A Wrapper around Scan to allow for SLAM usage.
Definition: SLAMScanWrapper.hpp:65
lvr2::SLAMScanWrapper::initialPose
const Transformd & initialPose() const
Returns the initial Pose of the Scan.
Definition: SLAMScanWrapper.cpp:168
lvr2::SLAMScanWrapper::addFrame
void addFrame(FrameUse use=FrameUse::UNUSED)
Adds a new animation Frame with the current Pose.
Definition: SLAMScanWrapper.cpp:178
lvr2::SLAMScanWrapper::deltaPose
const Transformd & deltaPose() const
Returns the difference between pose() and initialPose()
Definition: SLAMScanWrapper.cpp:163
lvr2::SLAMScanWrapper::m_points
std::vector< Vector3f > m_points
Definition: SLAMScanWrapper.hpp:213
lvr2::FrameUse::GRAPHSLAM
@ GRAPHSLAM
The Scan was part of a GraphSLAM Iteration.
transform
Definition: src/tools/lvr2_transform/Options.cpp:44
lvr2::SLAMScanWrapper::transform
virtual void transform(const Transformd &transform, bool writeFrame=true, FrameUse use=FrameUse::UPDATED)
Applies a relative Transformation to the Scan.
Definition: SLAMScanWrapper.cpp:78
lvr2::FrameUse::UPDATED
@ UPDATED
The Scan changed since the last Frame.
lvr2::Transformd
Transform< double > Transformd
4x4 double precision transformation matrix
Definition: MatrixTypes.hpp:71
lvr2::SLAMScanWrapper::getPosition
Vector3d getPosition() const
Get the Position of the Scan. Can also be obtained from pose()
Definition: SLAMScanWrapper.cpp:173
lvr2::FrameUse::UNUSED
@ UNUSED
The Scan did not change since the last Frame.
lvr2::writeFrame
void writeFrame(const Transform< T > &transform, const boost::filesystem::path &framesOut)
Writes a Eigen transformation into a .frames file.
lvr2::FrameUse::INVALID
@ INVALID
The Scan has not been registered yet.
ScanTypes.hpp
lvr2::SLAMScanWrapper::frame
const std::pair< Transformd, FrameUse > & frame(size_t index) const
Returns a Frame consisting of a Pose and a FrameUse.
Definition: SLAMScanWrapper.cpp:188
lvr2::Vector3f
Eigen::Vector3f Vector3f
Eigen 3D vector, single precision.
Definition: MatrixTypes.hpp:118
lvr2::SLAMScanWrapper::m_scan
ScanPtr m_scan
Definition: SLAMScanWrapper.hpp:211
lvr2::SLAMScanWrapper::rawPoint
const Vector3f & rawPoint(size_t index) const
Returns the Point at the specified index in local Coordinates.
Definition: SLAMScanWrapper.cpp:148
lvr2::SLAMScanWrapper::SLAMScanWrapper
SLAMScanWrapper(ScanPtr scan)
Construct a new SLAMScanWrapper object as a Wrapper around the Scan.
Definition: SLAMScanWrapper.cpp:45
lvr2::SLAMScanWrapper::m_numPoints
size_t m_numPoints
Definition: SLAMScanWrapper.hpp:214
lvr2::SLAMScanWrapper::setMinDistance
void setMinDistance(double minDistance)
Reduces the Scan by removing all Points closer than minDistance to the origin.
Definition: SLAMScanWrapper.cpp:95
lvr2::SLAMScanPtr
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
Definition: SLAMScanWrapper.hpp:221
lvr2::SLAMScanWrapper::writeFrames
void writeFrames(std::string path) const
Writes the Frames to the specified location.
Definition: SLAMScanWrapper.cpp:193
lvr2::Vector3d
Eigen::Vector3d Vector3d
Eigen 3D vector, double precision.
Definition: MatrixTypes.hpp:121
lvr2::FrameUse
FrameUse
Annotates the use of a Scan when creating an slam6D .frames file.
Definition: SLAMScanWrapper.hpp:48
lvr2::SLAMScanWrapper::innerScan
ScanPtr innerScan()
Access to the Scan that this instance is wrapped around.
Definition: SLAMScanWrapper.cpp:73
lvr2::SLAMScanWrapper::frameCount
size_t frameCount() const
Returns the number of Frames generated.
Definition: SLAMScanWrapper.cpp:183
lvr2::SLAMScanWrapper::reduce
void reduce(double voxelSize, int maxLeafSize)
Reduces the Scan using Octree Reduction.
Definition: SLAMScanWrapper.cpp:89
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::SLAMScanWrapper::m_deltaPose
Transformd m_deltaPose
Definition: SLAMScanWrapper.hpp:216
lvr2::SLAMScanWrapper::numPoints
size_t numPoints() const
Returns the number of Points in the Scan.
Definition: SLAMScanWrapper.cpp:153
lvr2::SLAMScanWrapper::~SLAMScanWrapper
virtual ~SLAMScanWrapper()=default
lvr2::FrameUse::LOOPCLOSE
@ LOOPCLOSE
The Scan was part of a Loopclose Iteration.
lvr2::SLAMScanWrapper::trim
void trim()
Reduces Memory usage by getting rid of Points removed with reduction Methods.
Definition: SLAMScanWrapper.cpp:135
lvr2::SLAMScanWrapper::point
virtual Vector3d point(size_t index) const
Returns the Point at the specified index in global Coordinates.
Definition: SLAMScanWrapper.cpp:141
lvr2::SLAMScanWrapper::pose
const Transformd & pose() const
Returns the current Pose of the Scan.
Definition: SLAMScanWrapper.cpp:158
lvr2::SLAMScanWrapper::m_frames
std::vector< std::pair< Transformd, FrameUse > > m_frames
Definition: SLAMScanWrapper.hpp:218
lvr2::ScanPtr
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
Definition: ScanTypes.hpp:98


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