Point Cloud Library (PCL)  1.11.1-dev
lum.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id: lum.h 5663 2012-05-02 13:49:39Z florentinus $
38  *
39  */
40 
41 #pragma once
42 
43 #include <pcl/common/transforms.h>
44 #include <pcl/registration/boost.h>
45 #include <pcl/registration/boost_graph.h>
46 #include <pcl/correspondence.h>
47 #include <pcl/memory.h>
48 #include <pcl/pcl_base.h>
49 #include <pcl/pcl_macros.h>
50 
51 namespace Eigen {
52 using Vector6f = Eigen::Matrix<float, 6, 1>;
53 using Matrix6f = Eigen::Matrix<float, 6, 6>;
54 } // namespace Eigen
55 
56 namespace pcl {
57 namespace registration {
58 /** \brief Globally Consistent Scan Matching based on an algorithm by Lu and Milios.
59  * \details A GraphSLAM algorithm where registration data is managed in a graph:
60  * <ul>
61  * <li>Vertices represent poses and hold the point cloud data and relative
62  * transformations.</li> <li>Edges represent pose constraints and hold the
63  * correspondence data between two point clouds.</li>
64  * </ul>
65  * Computation uses the first point cloud in the SLAM graph as a reference pose and
66  * attempts to align all other point clouds to it simultaneously. For more information:
67  * <ul><li>
68  * F. Lu, E. Milios,
69  * Globally Consistent Range Scan Alignment for Environment Mapping,
70  * Autonomous Robots 4, April 1997
71  * </li><li>
72  * Dorit Borrmann, Jan Elseberg, Kai Lingemann, Andreas Nüchter, and Joachim Hertzberg,
73  * The Efficient Extension of Globally Consistent Scan Matching to 6 DoF,
74  * In Proceedings of the 4th International Symposium on 3D Data Processing,
75  * Visualization and Transmission (3DPVT '08), June 2008
76  * </li></ul>
77  * Usage example:
78  * \code
79  * pcl::registration::LUM<pcl::PointXYZ> lum;
80  * // Add point clouds as vertices to the SLAM graph
81  * lum.addPointCloud (cloud_0);
82  * lum.addPointCloud (cloud_1);
83  * lum.addPointCloud (cloud_2);
84  * // Use your favorite pairwise correspondence estimation algorithm(s)
85  * corrs_0_to_1 = someAlgo (cloud_0, cloud_1);
86  * corrs_1_to_2 = someAlgo (cloud_1, cloud_2);
87  * corrs_2_to_0 = someAlgo (lum.getPointCloud (2), lum.getPointCloud (0));
88  * // Add the correspondence results as edges to the SLAM graph
89  * lum.setCorrespondences (0, 1, corrs_0_to_1);
90  * lum.setCorrespondences (1, 2, corrs_1_to_2);
91  * lum.setCorrespondences (2, 0, corrs_2_to_0);
92  * // Change the computation parameters
93  * lum.setMaxIterations (5);
94  * lum.setConvergenceThreshold (0.0);
95  * // Perform the actual LUM computation
96  * lum.compute ();
97  * // Return the concatenated point cloud result
98  * cloud_out = lum.getConcatenatedCloud ();
99  * // Return the separate point cloud transformations
100  * for(int i = 0; i < lum.getNumVertices (); i++)
101  * {
102  * transforms_out[i] = lum.getTransformation (i);
103  * }
104  * \endcode
105  * \author Frits Florentinus, Jochen Sprickerhof
106  * \ingroup registration
107  */
108 template <typename PointT>
109 class LUM {
110 public:
111  using Ptr = shared_ptr<LUM<PointT>>;
112  using ConstPtr = shared_ptr<const LUM<PointT>>;
113 
115  using PointCloudPtr = typename PointCloud::Ptr;
117 
122  };
123  struct EdgeProperties {
128  };
129 
130  using SLAMGraph = boost::adjacency_list<boost::eigen_vecS,
132  boost::bidirectionalS,
135  boost::no_property,
137  using SLAMGraphPtr = shared_ptr<SLAMGraph>;
138  using Vertex = typename SLAMGraph::vertex_descriptor;
139  using Edge = typename SLAMGraph::edge_descriptor;
140 
141  /** \brief Empty constructor.
142  */
143  LUM() : slam_graph_(new SLAMGraph), max_iterations_(5), convergence_threshold_(0.0) {}
144 
145  /** \brief Set the internal SLAM graph structure.
146  * \details All data used and produced by LUM is stored in this boost::adjacency_list.
147  * It is recommended to use the LUM class itself to build the graph.
148  * This method could otherwise be useful for managing several SLAM graphs in one
149  * instance of LUM. \param[in] slam_graph The new SLAM graph.
150  */
151  inline void
152  setLoopGraph(const SLAMGraphPtr& slam_graph);
153 
154  /** \brief Get the internal SLAM graph structure.
155  * \details All data used and produced by LUM is stored in this boost::adjacency_list.
156  * It is recommended to use the LUM class itself to build the graph.
157  * This method could otherwise be useful for managing several SLAM graphs in one
158  * instance of LUM. \return The current SLAM graph.
159  */
160  inline SLAMGraphPtr
161  getLoopGraph() const;
162 
163  /** \brief Get the number of vertices in the SLAM graph.
164  * \return The current number of vertices in the SLAM graph.
165  */
166  typename SLAMGraph::vertices_size_type
167  getNumVertices() const;
168 
169  /** \brief Set the maximum number of iterations for the compute() method.
170  * \details The compute() method finishes when max_iterations are met or when the
171  * convergence criteria is met. \param[in] max_iterations The new maximum number of
172  * iterations (default = 5).
173  */
174  void
175  setMaxIterations(int max_iterations);
176 
177  /** \brief Get the maximum number of iterations for the compute() method.
178  * \details The compute() method finishes when max_iterations are met or when the
179  * convergence criteria is met. \return The current maximum number of iterations
180  * (default = 5).
181  */
182  inline int
183  getMaxIterations() const;
184 
185  /** \brief Set the convergence threshold for the compute() method.
186  * \details When the compute() method computes the new poses relative to the old
187  * poses, it will determine the length of the difference vector. When the average
188  * length of all difference vectors becomes less than the convergence_threshold the
189  * convergence is assumed to be met. \param[in] convergence_threshold The new
190  * convergence threshold (default = 0.0).
191  */
192  void
193  setConvergenceThreshold(float convergence_threshold);
194 
195  /** \brief Get the convergence threshold for the compute() method.
196  * \details When the compute() method computes the new poses relative to the old
197  * poses, it will determine the length of the difference vector. When the average
198  * length of all difference vectors becomes less than the convergence_threshold the
199  * convergence is assumed to be met. \return The current convergence threshold
200  * (default = 0.0).
201  */
202  inline float
203  getConvergenceThreshold() const;
204 
205  /** \brief Add a new point cloud to the SLAM graph.
206  * \details This method will add a new vertex to the SLAM graph and attach a point
207  * cloud to that vertex. Optionally you can specify a pose estimate for this point
208  * cloud. A vertex' pose is always relative to the first vertex in the SLAM graph,
209  * i.e. the first point cloud that was added. Because this first vertex is the
210  * reference, you can not set a pose estimate for this vertex. Providing pose
211  * estimates to the vertices in the SLAM graph will reduce overall computation time of
212  * LUM. \note Vertex descriptors are typecastable to int. \param[in] cloud The new
213  * point cloud. \param[in] pose (optional) The pose estimate relative to the reference
214  * pose (first point cloud that was added). \return The vertex descriptor of the newly
215  * created vertex.
216  */
217  Vertex
218  addPointCloud(const PointCloudPtr& cloud,
219  const Eigen::Vector6f& pose = Eigen::Vector6f::Zero());
220 
221  /** \brief Change a point cloud on one of the SLAM graph's vertices.
222  * \details This method will change the point cloud attached to an existing vertex and
223  * will not alter the SLAM graph structure. Note that the correspondences attached to
224  * this vertex will not change and may need to be updated manually. \note Vertex
225  * descriptors are typecastable to int. \param[in] vertex The vertex descriptor of
226  * which to change the point cloud. \param[in] cloud The new point cloud for that
227  * vertex.
228  */
229  inline void
230  setPointCloud(const Vertex& vertex, const PointCloudPtr& cloud);
231 
232  /** \brief Return a point cloud from one of the SLAM graph's vertices.
233  * \note Vertex descriptors are typecastable to int.
234  * \param[in] vertex The vertex descriptor of which to return the point cloud.
235  * \return The current point cloud for that vertex.
236  */
237  inline PointCloudPtr
238  getPointCloud(const Vertex& vertex) const;
239 
240  /** \brief Change a pose estimate on one of the SLAM graph's vertices.
241  * \details A vertex' pose is always relative to the first vertex in the SLAM graph,
242  * i.e. the first point cloud that was added. Because this first vertex is the
243  * reference, you can not set a pose estimate for this vertex. Providing pose
244  * estimates to the vertices in the SLAM graph will reduce overall computation time of
245  * LUM. \note Vertex descriptors are typecastable to int. \param[in] vertex The vertex
246  * descriptor of which to set the pose estimate. \param[in] pose The new pose estimate
247  * for that vertex.
248  */
249  inline void
250  setPose(const Vertex& vertex, const Eigen::Vector6f& pose);
251 
252  /** \brief Return a pose estimate from one of the SLAM graph's vertices.
253  * \note Vertex descriptors are typecastable to int.
254  * \param[in] vertex The vertex descriptor of which to return the pose estimate.
255  * \return The current pose estimate of that vertex.
256  */
257  inline Eigen::Vector6f
258  getPose(const Vertex& vertex) const;
259 
260  /** \brief Return a pose estimate from one of the SLAM graph's vertices as an affine
261  * transformation matrix. \note Vertex descriptors are typecastable to int. \param[in]
262  * vertex The vertex descriptor of which to return the transformation matrix. \return
263  * The current transformation matrix of that vertex.
264  */
265  inline Eigen::Affine3f
266  getTransformation(const Vertex& vertex) const;
267 
268  /** \brief Add/change a set of correspondences for one of the SLAM graph's edges.
269  * \details The edges in the SLAM graph are directional and point from source vertex
270  * to target vertex. The query indices of the correspondences, index the points at the
271  * source vertex' point cloud. The matching indices of the correspondences, index the
272  * points at the target vertex' point cloud. If no edge was present at the specified
273  * location, this method will add a new edge to the SLAM graph and attach the
274  * correspondences to that edge. If the edge was already present, this method will
275  * overwrite the correspondence information of that edge and will not alter the SLAM
276  * graph structure. \note Vertex descriptors are typecastable to int. \param[in]
277  * source_vertex The vertex descriptor of the correspondences' source point cloud.
278  * \param[in] target_vertex The vertex descriptor of the correspondences' target point
279  * cloud. \param[in] corrs The new set of correspondences for that edge.
280  */
281  void
282  setCorrespondences(const Vertex& source_vertex,
283  const Vertex& target_vertex,
284  const pcl::CorrespondencesPtr& corrs);
285 
286  /** \brief Return a set of correspondences from one of the SLAM graph's edges.
287  * \note Vertex descriptors are typecastable to int.
288  * \param[in] source_vertex The vertex descriptor of the correspondences' source point
289  * cloud. \param[in] target_vertex The vertex descriptor of the correspondences'
290  * target point cloud. \return The current set of correspondences of that edge.
291  */
293  getCorrespondences(const Vertex& source_vertex, const Vertex& target_vertex) const;
294 
295  /** \brief Perform LUM's globally consistent scan matching.
296  * \details Computation uses the first point cloud in the SLAM graph as a reference
297  * pose and attempts to align all other point clouds to it simultaneously. <br> Things
298  * to keep in mind: <ul> <li>Only those parts of the graph connected to the reference
299  * pose will properly align to it.</li> <li>All sets of correspondences should span
300  * the same space and need to be sufficient to determine a rigid transformation.</li>
301  * <li>The algorithm draws it strength from loops in the graph because it will
302  * distribute errors evenly amongst those loops.</li>
303  * </ul>
304  * Computation ends when either of the following conditions hold:
305  * <ul>
306  * <li>The number of iterations reaches max_iterations. Use setMaxIterations() to
307  * change.</li> <li>The convergence criteria is met. Use setConvergenceThreshold() to
308  * change.</li>
309  * </ul>
310  * Computation will change the pose estimates for the vertices of the SLAM graph, not
311  * the point clouds attached to them. The results can be retrieved with getPose(),
312  * getTransformation(), getTransformedCloud() or getConcatenatedCloud().
313  */
314  void
315  compute();
316 
317  /** \brief Return a point cloud from one of the SLAM graph's vertices compounded onto
318  * its current pose estimate. \note Vertex descriptors are typecastable to int.
319  * \param[in] vertex The vertex descriptor of which to return the transformed point
320  * cloud. \return The transformed point cloud of that vertex.
321  */
322  PointCloudPtr
323  getTransformedCloud(const Vertex& vertex) const;
324 
325  /** \brief Return a concatenated point cloud of all the SLAM graph's point clouds
326  * compounded onto their current pose estimates. \return The concatenated transformed
327  * point clouds of the entire SLAM graph.
328  */
329  PointCloudPtr
330  getConcatenatedCloud() const;
331 
332 protected:
333  /** \brief Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_).
334  */
335  void
336  computeEdge(const Edge& e);
337 
338  /** \brief Returns a pose corrected 6DoF incidence matrix. */
339  inline Eigen::Matrix6f
341 
342 private:
343  /** \brief The internal SLAM graph structure. */
344  SLAMGraphPtr slam_graph_;
345 
346  /** \brief The maximum number of iterations for the compute() method. */
347  int max_iterations_;
348 
349  /** \brief The convergence threshold for the summed vector lengths of all poses. */
350  float convergence_threshold_;
351 };
352 } // namespace registration
353 } // namespace pcl
354 
355 #ifdef PCL_NO_PRECOMPILE
356 #include <pcl/registration/impl/lum.hpp>
357 #endif
boost::eigen_vecS
Definition: boost_graph.h:50
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl::registration::LUM::getCorrespondences
pcl::CorrespondencesPtr getCorrespondences(const Vertex &source_vertex, const Vertex &target_vertex) const
Return a set of correspondences from one of the SLAM graph's edges.
Definition: lum.hpp:200
pcl
Definition: convolution.h:46
pcl::registration::LUM::getConvergenceThreshold
float getConvergenceThreshold() const
Get the convergence threshold for the compute() method.
Definition: lum.hpp:94
Eigen
Definition: bfgs.h:10
pcl::registration::LUM::PointCloudPtr
typename PointCloud::Ptr PointCloudPtr
Definition: lum.h:115
pcl::registration::LUM::EdgeProperties::cinv_
Eigen::Matrix6f cinv_
Definition: lum.h:125
pcl::registration::LUM
Globally Consistent Scan Matching based on an algorithm by Lu and Milios.
Definition: lum.h:109
pcl::registration::LUM::setPose
void setPose(const Vertex &vertex, const Eigen::Vector6f &pose)
Change a pose estimate on one of the SLAM graph's vertices.
Definition: lum.hpp:142
pcl::registration::LUM::Vertex
typename SLAMGraph::vertex_descriptor Vertex
Definition: lum.h:138
pcl::registration::LUM::setCorrespondences
void setCorrespondences(const Vertex &source_vertex, const Vertex &target_vertex, const pcl::CorrespondencesPtr &corrs)
Add/change a set of correspondences for one of the SLAM graph's edges.
Definition: lum.hpp:179
pcl::registration::LUM::LUM
LUM()
Empty constructor.
Definition: lum.h:143
Eigen::Matrix6f
Eigen::Matrix< float, 6, 6 > Matrix6f
Definition: lum.h:53
pcl::registration::LUM::setLoopGraph
void setLoopGraph(const SLAMGraphPtr &slam_graph)
Set the internal SLAM graph structure.
Definition: lum.hpp:52
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
pcl::registration::LUM::compute
void compute()
Perform LUM's globally consistent scan matching.
Definition: lum.hpp:221
pcl::registration::LUM::incidenceCorrection
Eigen::Matrix6f incidenceCorrection(const Eigen::Vector6f &pose)
Returns a pose corrected 6DoF incidence matrix.
Definition: lum.hpp:446
pcl::registration::LUM::Edge
typename SLAMGraph::edge_descriptor Edge
Definition: lum.h:139
Eigen::Vector6f
Eigen::Matrix< float, 6, 1 > Vector6f
Definition: lum.h:52
pcl::registration::LUM::EdgeProperties::corrs_
pcl::CorrespondencesPtr corrs_
Definition: lum.h:124
pcl::registration::LUM::getPointCloud
PointCloudPtr getPointCloud(const Vertex &vertex) const
Return a point cloud from one of the SLAM graph's vertices.
Definition: lum.hpp:130
pcl::registration::LUM::ConstPtr
shared_ptr< const LUM< PointT > > ConstPtr
Definition: lum.h:112
pcl::registration::LUM::PointCloudConstPtr
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: lum.h:116
pcl::registration::LUM::SLAMGraphPtr
shared_ptr< SLAMGraph > SLAMGraphPtr
Definition: lum.h:137
pcl::registration::LUM::addPointCloud
Vertex addPointCloud(const PointCloudPtr &cloud, const Eigen::Vector6f &pose=Eigen::Vector6f::Zero())
Add a new point cloud to the SLAM graph.
Definition: lum.hpp:101
pcl::registration::LUM::EdgeProperties
Definition: lum.h:123
pcl::registration::LUM::getPose
Eigen::Vector6f getPose(const Vertex &vertex) const
Return a pose estimate from one of the SLAM graph's vertices.
Definition: lum.hpp:159
pcl::registration::LUM::getTransformation
Eigen::Affine3f getTransformation(const Vertex &vertex) const
Return a pose estimate from one of the SLAM graph's vertices as an affine transformation matrix.
Definition: lum.hpp:171
pcl::registration::LUM::setPointCloud
void setPointCloud(const Vertex &vertex, const PointCloudPtr &cloud)
Change a point cloud on one of the SLAM graph's vertices.
Definition: lum.hpp:118
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
boost::eigen_listS
Definition: boost_graph.h:70
pcl::registration::LUM::VertexProperties::pose_
Eigen::Vector6f pose_
Definition: lum.h:120
pcl::registration::LUM::getLoopGraph
SLAMGraphPtr getLoopGraph() const
Get the internal SLAM graph structure.
Definition: lum.hpp:59
pcl::registration::LUM::Ptr
shared_ptr< LUM< PointT > > Ptr
Definition: lum.h:111
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:406
pcl::registration::LUM::computeEdge
void computeEdge(const Edge &e)
Linearized computation of C^-1 and C^-1*D (results stored in slam_graph_).
Definition: lum.hpp:308
pcl::registration::LUM::VertexProperties
Definition: lum.h:118
pcl::registration::LUM::getTransformedCloud
PointCloudPtr getTransformedCloud(const Vertex &vertex) const
Return a point cloud from one of the SLAM graph's vertices compounded onto its current pose estimate.
Definition: lum.hpp:285
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:407
pcl::registration::LUM::getMaxIterations
int getMaxIterations() const
Get the maximum number of iterations for the compute() method.
Definition: lum.hpp:80
pcl::registration::LUM::setMaxIterations
void setMaxIterations(int max_iterations)
Set the maximum number of iterations for the compute() method.
Definition: lum.hpp:73
pcl::registration::LUM::setConvergenceThreshold
void setConvergenceThreshold(float convergence_threshold)
Set the convergence threshold for the compute() method.
Definition: lum.hpp:87
pcl::registration::LUM::getNumVertices
SLAMGraph::vertices_size_type getNumVertices() const
Get the number of vertices in the SLAM graph.
Definition: lum.hpp:66
pcl::CorrespondencesPtr
shared_ptr< Correspondences > CorrespondencesPtr
Definition: correspondence.h:90
pcl::registration::LUM::VertexProperties::cloud_
PointCloudPtr cloud_
Definition: lum.h:119
pcl::registration::LUM::EdgeProperties::cinvd_
Eigen::Vector6f cinvd_
Definition: lum.h:126
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::Edge
Definition: edge.h:49
pcl::registration::LUM::getConcatenatedCloud
PointCloudPtr getConcatenatedCloud() const
Return a concatenated point cloud of all the SLAM graph's point clouds compounded onto their current ...
Definition: lum.hpp:294
pcl::registration::LUM::SLAMGraph
boost::adjacency_list< boost::eigen_vecS, boost::eigen_vecS, boost::bidirectionalS, VertexProperties, EdgeProperties, boost::no_property, boost::eigen_listS > SLAMGraph
Definition: lum.h:136