34 #ifndef SLAMSCANWRAPPER_HPP_ 35 #define SLAMSCANWRAPPER_HPP_ 39 #include <Eigen/Dense> 110 void reduce(
double voxelSize,
int maxLeafSize);
119 void setMinDistance(
double minDistance);
128 void setMaxDistance(
double maxDistance);
142 virtual Vector3d point(
size_t index)
const;
150 const Vector3f& rawPoint(
size_t index)
const;
157 size_t numPoints()
const;
193 size_t frameCount()
const;
201 const std::pair<Transformd, FrameUse>& frame(
size_t index)
const;
208 void writeFrames(std::string path)
const;
218 std::vector<std::pair<Transformd, FrameUse>>
m_frames;
The Scan did not change since the last Frame.
The Scan was part of a GraphSLAM Iteration.
The Scan changed since the last Frame.
Eigen::Vector3d Vector3d
Eigen 3D vector, double precision.
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
Transform< double > Transformd
4x4 double precision transformation matrix
The Scan has not been registered yet.
std::vector< Vector3f > m_points
Eigen::Vector3f Vector3f
Eigen 3D vector, single precision.
A Wrapper around Scan to allow for SLAM usage.
The Scan was part of a Loopclose Iteration.
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
void writeFrame(const Transform< T > &transform, const boost::filesystem::path &framesOut)
Writes a Eigen transformation into a .frames file.
std::vector< std::pair< Transformd, FrameUse > > m_frames
PointBufferPtr transform(PointBufferPtr pc_in, const Transformd &T)
FrameUse
Annotates the use of a Scan when creating an slam6D .frames file.