SLAMScanWrapper.cpp
Go to the documentation of this file.
1 
37 
38 #include <fstream>
39 
40 using namespace std;
41 
42 namespace lvr2
43 {
44 
45 SLAMScanWrapper::SLAMScanWrapper(ScanPtr scan)
46  : m_scan(scan), m_deltaPose(Transformd::Identity())
47 {
48  if (m_scan)
49  {
50  m_scan->registration = m_scan->poseEstimation;
51 
52  // TODO: m_scan->m_points->load();
53 
54  m_numPoints = m_scan->points->numPoints();
55  lvr2::floatArr arr = m_scan->points->getPointArray();
56 
57  m_points.resize(m_numPoints);
58  #pragma omp parallel for schedule(static)
59  for (size_t i = 0; i < m_numPoints; i++)
60  {
61  m_points[i] = Vector3f(arr[i * 3], arr[i * 3 + 1], arr[i * 3 + 2]);
62  }
63 
64  // TODO: m_scan->m_points->unload();
65  m_scan->points.reset();
66  }
67  else
68  {
69  m_numPoints = 0;
70  }
71 }
72 
74 {
75  return m_scan;
76 }
77 
79 {
80  m_scan->registration = transform * m_scan->registration;
82 
83  if (writeFrame)
84  {
85  addFrame(use);
86  }
87 }
88 
89 void SLAMScanWrapper::reduce(double voxelSize, int maxLeafSize)
90 {
91  m_numPoints = octreeReduce(m_points.data(), m_numPoints, voxelSize, maxLeafSize);
92  m_points.resize(m_numPoints);
93 }
94 
95 void SLAMScanWrapper::setMinDistance(double minDistance)
96 {
97  double sqDist = minDistance * minDistance;
98 
99  size_t cur = 0;
100  while (cur < m_numPoints)
101  {
102  if (m_points[cur].squaredNorm() <= sqDist)
103  {
104  m_points[cur] = m_points[m_numPoints - 1];
105  m_numPoints--;
106  }
107  else
108  {
109  cur++;
110  }
111  }
112  m_points.resize(m_numPoints);
113 }
114 
115 void SLAMScanWrapper::setMaxDistance(double maxDistance)
116 {
117  double sqDist = maxDistance * maxDistance;
118 
119  size_t cur = 0;
120  while (cur < m_numPoints)
121  {
122  if (m_points[cur].squaredNorm() >= sqDist)
123  {
124  m_points[cur] = m_points[m_numPoints - 1];
125  m_numPoints--;
126  }
127  else
128  {
129  cur++;
130  }
131  }
132  m_points.resize(m_numPoints);
133 }
134 
136 {
137  m_points.resize(m_numPoints);
138  m_points.shrink_to_fit();
139 }
140 
141 Vector3d SLAMScanWrapper::point(size_t index) const
142 {
143  const Vector3f& p = m_points[index];
144  Vector4d extended(p.x(), p.y(), p.z(), 1.0);
145  return (pose() * extended).block<3, 1>(0, 0);
146 }
147 
148 const Vector3f& SLAMScanWrapper::rawPoint(size_t index) const
149 {
150  return m_points[index];
151 }
152 
154 {
155  return m_numPoints;
156 }
157 
159 {
160  return m_scan->registration;
161 }
162 
164 {
165  return m_deltaPose;
166 }
167 
169 {
170  return m_scan->poseEstimation;
171 }
172 
174 {
175  return pose().block<3, 1>(0, 3);
176 }
177 
179 {
180  m_frames.push_back(make_pair(pose(), use));
181 }
182 
184 {
185  return m_frames.size();
186 }
187 
188 const std::pair<Transformd, FrameUse>& SLAMScanWrapper::frame(size_t index) const
189 {
190  return m_frames[index];
191 }
192 
193 void SLAMScanWrapper::writeFrames(std::string path) const
194 {
195  ofstream out(path);
196  for (const std::pair<Transformd, FrameUse>& frame : m_frames)
197  {
198  for (int i = 0; i < 16; i++)
199  {
200  out << frame.first(i) << " ";
201  }
202 
203  out << (int)frame.second << endl;
204  }
205 }
206 
207 } /* namespace lvr2 */
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
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::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
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::octreeReduce
int octreeReduce(Vector3f *points, int n, double voxelSize, int maxLeafSize)
Reduces a Point Cloud using an Octree with a minimum Voxel size.
Definition: TreeUtils.cpp:130
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::writeFrame
void writeFrame(const Transform< T > &transform, const boost::filesystem::path &framesOut)
Writes a Eigen transformation into a .frames file.
SLAMScanWrapper.hpp
p
SharedPointer p
Definition: ConvertShared.hpp:42
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::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::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
TreeUtils.hpp
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
std
Definition: HalfEdge.hpp:124
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::Vector4d
Eigen::Vector4d Vector4d
Eigen 4D vector, double precision.
Definition: MatrixTypes.hpp:134
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::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