Point Cloud Library (PCL)  1.9.1
ndt_2d.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2011, 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$
38  *
39  */
40 
41 #ifndef PCL_NDT_2D_H_
42 #define PCL_NDT_2D_H_
43 
44 #include <pcl/registration/registration.h>
45 
46 namespace pcl
47 {
48  /** \brief @b NormalDistributionsTransform2D provides an implementation of the
49  * Normal Distributions Transform algorithm for scan matching.
50  *
51  * This implementation is intended to match the definition:
52  * Peter Biber and Wolfgang Straßer. The normal distributions transform: A
53  * new approach to laser scan matching. In Proceedings of the IEEE In-
54  * ternational Conference on Intelligent Robots and Systems (IROS), pages
55  * 2743–2748, Las Vegas, USA, October 2003.
56  *
57  * \author James Crosby
58  */
59  template <typename PointSource, typename PointTarget>
60  class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget>
61  {
62  typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
63  typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
64  typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
65 
66  typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
67 
68  typedef PointIndices::Ptr PointIndicesPtr;
69  typedef PointIndices::ConstPtr PointIndicesConstPtr;
70 
71  public:
72 
73  typedef boost::shared_ptr< NormalDistributionsTransform2D<PointSource, PointTarget> > Ptr;
74  typedef boost::shared_ptr< const NormalDistributionsTransform2D<PointSource, PointTarget> > ConstPtr;
75 
76  /** \brief Empty constructor. */
78  : Registration<PointSource,PointTarget> (),
79  grid_centre_ (0,0), grid_step_ (1,1), grid_extent_ (20,20), newton_lambda_ (1,1,1)
80  {
81  reg_name_ = "NormalDistributionsTransform2D";
82  }
83 
84  /** \brief Empty destructor */
86 
87  /** \brief centre of the ndt grid (target coordinate system)
88  * \param centre value to set
89  */
90  virtual void
91  setGridCentre (const Eigen::Vector2f& centre) { grid_centre_ = centre; }
92 
93  /** \brief Grid spacing (step) of the NDT grid
94  * \param[in] step value to set
95  */
96  virtual void
97  setGridStep (const Eigen::Vector2f& step) { grid_step_ = step; }
98 
99  /** \brief NDT Grid extent (in either direction from the grid centre)
100  * \param[in] extent value to set
101  */
102  virtual void
103  setGridExtent (const Eigen::Vector2f& extent) { grid_extent_ = extent; }
104 
105  /** \brief NDT Newton optimisation step size parameter
106  * \param[in] lambda step size: 1 is simple newton optimisation, smaller values may improve convergence
107  */
108  virtual void
109  setOptimizationStepSize (const double& lambda) { newton_lambda_ = Eigen::Vector3d (lambda, lambda, lambda); }
110 
111  /** \brief NDT Newton optimisation step size parameter
112  * \param[in] lambda step size: (1,1,1) is simple newton optimisation,
113  * smaller values may improve convergence, or elements may be set to
114  * zero to prevent optimisation over some parameters
115  *
116  * This overload allows control of updates to the individual (x, y,
117  * theta) free parameters in the optimisation. If, for example, theta is
118  * believed to be close to the correct value a small value of lambda[2]
119  * should be used.
120  */
121  virtual void
122  setOptimizationStepSize (const Eigen::Vector3d& lambda) { newton_lambda_ = lambda; }
123 
124  protected:
125  /** \brief Rigid transformation computation method with initial guess.
126  * \param[out] output the transformed input point cloud dataset using the rigid transformation found
127  * \param[in] guess the initial guess of the transformation to compute
128  */
129  virtual void
130  computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
131 
144 
145  Eigen::Vector2f grid_centre_;
146  Eigen::Vector2f grid_step_;
147  Eigen::Vector2f grid_extent_;
148  Eigen::Vector3d newton_lambda_;
149  public:
150  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
151  };
152 
153 } // namespace pcl
154 
155 #include <pcl/registration/impl/ndt_2d.hpp>
156 
157 #endif // ndef PCL_NDT_2D_H_
158 
pcl
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
pcl::NormalDistributionsTransform2D::setGridStep
virtual void setGridStep(const Eigen::Vector2f &step)
Grid spacing (step) of the NDT grid.
Definition: ndt_2d.h:97
pcl::Registration
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:62
pcl::NormalDistributionsTransform2D::newton_lambda_
Eigen::Vector3d newton_lambda_
Definition: ndt_2d.h:148
pcl::NormalDistributionsTransform2D::NormalDistributionsTransform2D
NormalDistributionsTransform2D()
Empty constructor.
Definition: ndt_2d.h:77
pcl::NormalDistributionsTransform2D
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algor...
Definition: ndt_2d.h:60
pcl::NormalDistributionsTransform2D::computeTransformation
virtual void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess)
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:377
pcl::NormalDistributionsTransform2D::Ptr
boost::shared_ptr< NormalDistributionsTransform2D< PointSource, PointTarget > > Ptr
Definition: ndt_2d.h:73
pcl::PointIndices::Ptr
boost::shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:22
pcl::NormalDistributionsTransform2D::grid_centre_
Eigen::Vector2f grid_centre_
Definition: ndt_2d.h:145
pcl::NormalDistributionsTransform2D::ConstPtr
boost::shared_ptr< const NormalDistributionsTransform2D< PointSource, PointTarget > > ConstPtr
Definition: ndt_2d.h:74
pcl::NormalDistributionsTransform2D::setGridExtent
virtual void setGridExtent(const Eigen::Vector2f &extent)
NDT Grid extent (in either direction from the grid centre)
Definition: ndt_2d.h:103
pcl::NormalDistributionsTransform2D::setOptimizationStepSize
virtual void setOptimizationStepSize(const double &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:109
pcl::NormalDistributionsTransform2D::grid_step_
Eigen::Vector2f grid_step_
Definition: ndt_2d.h:146
pcl::NormalDistributionsTransform2D::setOptimizationStepSize
virtual void setOptimizationStepSize(const Eigen::Vector3d &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:122
pcl::PointIndices::ConstPtr
boost::shared_ptr< ::pcl::PointIndices const > ConstPtr
Definition: PointIndices.h:23
pcl::NormalDistributionsTransform2D::~NormalDistributionsTransform2D
virtual ~NormalDistributionsTransform2D()
Empty destructor.
Definition: ndt_2d.h:85
pcl::NormalDistributionsTransform2D::grid_extent_
Eigen::Vector2f grid_extent_
Definition: ndt_2d.h:147
pcl::Registration< PointSource, PointTarget >::reg_name_
std::string reg_name_
The registration method name.
Definition: registration.h:482
pcl::NormalDistributionsTransform2D::setGridCentre
virtual void setGridCentre(const Eigen::Vector2f &centre)
centre of the ndt grid (target coordinate system)
Definition: ndt_2d.h:91