Point Cloud Library (PCL)  1.14.1-dev
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 #pragma once
42 
43 #include <pcl/registration/registration.h>
44 #include <pcl/memory.h>
45 
46 namespace pcl {
47 /** \brief @b NormalDistributionsTransform2D provides an implementation of the
48  * Normal Distributions Transform algorithm for scan matching.
49  *
50  * This implementation is intended to match the definition:
51  * Peter Biber and Wolfgang Straßer. The normal distributions transform: A
52  * new approach to laser scan matching. In Proceedings of the IEEE In-
53  * ternational Conference on Intelligent Robots and Systems (IROS), pages
54  * 2743–2748, Las Vegas, USA, October 2003.
55  *
56  * \author James Crosby
57  * \ingroup registration
58  */
59 template <typename PointSource, typename PointTarget>
60 class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget> {
61  using PointCloudSource =
63  using PointCloudSourcePtr = typename PointCloudSource::Ptr;
64  using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
65 
66  using PointCloudTarget =
68 
69  using PointIndicesPtr = PointIndices::Ptr;
70  using PointIndicesConstPtr = PointIndices::ConstPtr;
71 
72 public:
73  using Ptr = shared_ptr<NormalDistributionsTransform2D<PointSource, PointTarget>>;
74  using ConstPtr =
75  shared_ptr<const NormalDistributionsTransform2D<PointSource, PointTarget>>;
76 
77  /** \brief Empty constructor. */
79  : Registration<PointSource, PointTarget>()
80  , grid_centre_(0, 0)
81  , grid_step_(1, 1)
82  , grid_extent_(20, 20)
83  , newton_lambda_(1, 1, 1)
84  {
85  reg_name_ = "NormalDistributionsTransform2D";
86  }
87 
88  /** \brief Empty destructor */
89  ~NormalDistributionsTransform2D() override = default;
90 
91  /** \brief centre of the ndt grid (target coordinate system)
92  * \param centre value to set
93  */
94  virtual void
95  setGridCentre(const Eigen::Vector2f& centre)
96  {
97  grid_centre_ = centre;
98  }
99 
100  /** \brief Grid spacing (step) of the NDT grid
101  * \param[in] step value to set
102  */
103  virtual void
104  setGridStep(const Eigen::Vector2f& step)
105  {
106  grid_step_ = step;
107  }
108 
109  /** \brief NDT Grid extent (in either direction from the grid centre)
110  * \param[in] extent value to set
111  */
112  virtual void
113  setGridExtent(const Eigen::Vector2f& extent)
114  {
115  grid_extent_ = extent;
116  }
117 
118  /** \brief NDT Newton optimisation step size parameter
119  * \param[in] lambda step size: 1 is simple newton optimisation, smaller values may
120  * improve convergence
121  */
122  virtual void
123  setOptimizationStepSize(const double& lambda)
124  {
125  newton_lambda_ = Eigen::Vector3d(lambda, lambda, lambda);
126  }
127 
128  /** \brief NDT Newton optimisation step size parameter
129  * \param[in] lambda step size: (1,1,1) is simple newton optimisation,
130  * smaller values may improve convergence, or elements may be set to
131  * zero to prevent optimisation over some parameters
132  *
133  * This overload allows control of updates to the individual (x, y,
134  * theta) free parameters in the optimisation. If, for example, theta is
135  * believed to be close to the correct value a small value of lambda[2]
136  * should be used.
137  */
138  virtual void
139  setOptimizationStepSize(const Eigen::Vector3d& lambda)
140  {
141  newton_lambda_ = lambda;
142  }
143 
144 protected:
145  /** \brief Rigid transformation computation method with initial guess.
146  * \param[out] output the transformed input point cloud dataset using the rigid
147  * transformation found \param[in] guess the initial guess of the transformation to
148  * compute
149  */
150  void
151  computeTransformation(PointCloudSource& output,
152  const Eigen::Matrix4f& guess) override;
153 
166 
167  Eigen::Vector2f grid_centre_;
168  Eigen::Vector2f grid_step_;
169  Eigen::Vector2f grid_extent_;
170  Eigen::Vector3d newton_lambda_;
171 
172 public:
174 };
175 
176 } // namespace pcl
177 
178 #include <pcl/registration/impl/ndt_2d.hpp>
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algor...
Definition: ndt_2d.h:60
virtual void setOptimizationStepSize(const double &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:123
virtual void setOptimizationStepSize(const Eigen::Vector3d &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:139
~NormalDistributionsTransform2D() override=default
Empty destructor.
virtual void setGridStep(const Eigen::Vector2f &step)
Grid spacing (step) of the NDT grid.
Definition: ndt_2d.h:104
virtual void setGridExtent(const Eigen::Vector2f &extent)
NDT Grid extent (in either direction from the grid centre)
Definition: ndt_2d.h:113
virtual void setGridCentre(const Eigen::Vector2f &centre)
centre of the ndt grid (target coordinate system)
Definition: ndt_2d.h:95
Eigen::Vector3d newton_lambda_
Definition: ndt_2d.h:170
NormalDistributionsTransform2D()
Empty constructor.
Definition: ndt_2d.h:78
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:392
shared_ptr< NormalDistributionsTransform2D< PointSource, PointTarget > > Ptr
Definition: ndt_2d.h:73
shared_ptr< const NormalDistributionsTransform2D< PointSource, PointTarget > > ConstPtr
Definition: ndt_2d.h:75
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
std::string reg_name_
The registration method name.
Definition: registration.h:548
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:86
Defines functions, macros and traits for allocating and using memory.
shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:13
shared_ptr< const ::pcl::PointIndices > ConstPtr
Definition: PointIndices.h:14