Point Cloud Library (PCL)  1.11.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  */
58 template <typename PointSource, typename PointTarget>
59 class NormalDistributionsTransform2D : public Registration<PointSource, PointTarget> {
60  using PointCloudSource =
62  using PointCloudSourcePtr = typename PointCloudSource::Ptr;
63  using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
64 
65  using PointCloudTarget =
67 
68  using PointIndicesPtr = PointIndices::Ptr;
69  using PointIndicesConstPtr = PointIndices::ConstPtr;
70 
71 public:
72  using Ptr = shared_ptr<NormalDistributionsTransform2D<PointSource, PointTarget>>;
73  using ConstPtr =
74  shared_ptr<const NormalDistributionsTransform2D<PointSource, PointTarget>>;
75 
76  /** \brief Empty constructor. */
78  : Registration<PointSource, PointTarget>()
79  , grid_centre_(0, 0)
80  , grid_step_(1, 1)
81  , grid_extent_(20, 20)
82  , newton_lambda_(1, 1, 1)
83  {
84  reg_name_ = "NormalDistributionsTransform2D";
85  }
86 
87  /** \brief Empty destructor */
89 
90  /** \brief centre of the ndt grid (target coordinate system)
91  * \param centre value to set
92  */
93  virtual void
94  setGridCentre(const Eigen::Vector2f& centre)
95  {
96  grid_centre_ = centre;
97  }
98 
99  /** \brief Grid spacing (step) of the NDT grid
100  * \param[in] step value to set
101  */
102  virtual void
103  setGridStep(const Eigen::Vector2f& step)
104  {
105  grid_step_ = step;
106  }
107 
108  /** \brief NDT Grid extent (in either direction from the grid centre)
109  * \param[in] extent value to set
110  */
111  virtual void
112  setGridExtent(const Eigen::Vector2f& extent)
113  {
114  grid_extent_ = extent;
115  }
116 
117  /** \brief NDT Newton optimisation step size parameter
118  * \param[in] lambda step size: 1 is simple newton optimisation, smaller values may
119  * improve convergence
120  */
121  virtual void
122  setOptimizationStepSize(const double& lambda)
123  {
124  newton_lambda_ = Eigen::Vector3d(lambda, lambda, lambda);
125  }
126 
127  /** \brief NDT Newton optimisation step size parameter
128  * \param[in] lambda step size: (1,1,1) is simple newton optimisation,
129  * smaller values may improve convergence, or elements may be set to
130  * zero to prevent optimisation over some parameters
131  *
132  * This overload allows control of updates to the individual (x, y,
133  * theta) free parameters in the optimisation. If, for example, theta is
134  * believed to be close to the correct value a small value of lambda[2]
135  * should be used.
136  */
137  virtual void
138  setOptimizationStepSize(const Eigen::Vector3d& lambda)
139  {
140  newton_lambda_ = lambda;
141  }
142 
143 protected:
144  /** \brief Rigid transformation computation method with initial guess.
145  * \param[out] output the transformed input point cloud dataset using the rigid
146  * transformation found \param[in] guess the initial guess of the transformation to
147  * compute
148  */
149  void
150  computeTransformation(PointCloudSource& output,
151  const Eigen::Matrix4f& guess) override;
152 
165 
166  Eigen::Vector2f grid_centre_;
167  Eigen::Vector2f grid_step_;
168  Eigen::Vector2f grid_extent_;
169  Eigen::Vector3d newton_lambda_;
170 
171 public:
173 };
174 
175 } // namespace pcl
176 
177 #include <pcl/registration/impl/ndt_2d.hpp>
pcl
Definition: convolution.h:46
pcl::NormalDistributionsTransform2D::setGridStep
virtual void setGridStep(const Eigen::Vector2f &step)
Grid spacing (step) of the NDT grid.
Definition: ndt_2d.h:103
pcl::Registration
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
pcl::NormalDistributionsTransform2D::newton_lambda_
Eigen::Vector3d newton_lambda_
Definition: ndt_2d.h:169
pcl::NormalDistributionsTransform2D::NormalDistributionsTransform2D
NormalDistributionsTransform2D()
Empty constructor.
Definition: ndt_2d.h:77
pcl::NormalDistributionsTransform2D::Ptr
shared_ptr< NormalDistributionsTransform2D< PointSource, PointTarget > > Ptr
Definition: ndt_2d.h:72
pcl::NormalDistributionsTransform2D
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algor...
Definition: ndt_2d.h:59
pcl::NormalDistributionsTransform2D::computeTransformation
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:391
pcl::NormalDistributionsTransform2D::grid_centre_
Eigen::Vector2f grid_centre_
Definition: ndt_2d.h:166
pcl::PointIndices::ConstPtr
shared_ptr< const ::pcl::PointIndices > ConstPtr
Definition: PointIndices.h:14
pcl::NormalDistributionsTransform2D::setGridExtent
virtual void setGridExtent(const Eigen::Vector2f &extent)
NDT Grid extent (in either direction from the grid centre)
Definition: ndt_2d.h:112
pcl::NormalDistributionsTransform2D::setOptimizationStepSize
virtual void setOptimizationStepSize(const double &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:122
pcl::NormalDistributionsTransform2D::grid_step_
Eigen::Vector2f grid_step_
Definition: ndt_2d.h:167
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::NormalDistributionsTransform2D::setOptimizationStepSize
virtual void setOptimizationStepSize(const Eigen::Vector3d &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:138
pcl::PointIndices::Ptr
shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:13
pcl::NormalDistributionsTransform2D::grid_extent_
Eigen::Vector2f grid_extent_
Definition: ndt_2d.h:168
pcl::NormalDistributionsTransform2D::ConstPtr
shared_ptr< const NormalDistributionsTransform2D< PointSource, PointTarget > > ConstPtr
Definition: ndt_2d.h:74
pcl::NormalDistributionsTransform2D::~NormalDistributionsTransform2D
~NormalDistributionsTransform2D()
Empty destructor.
Definition: ndt_2d.h:88
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::Registration< PointSource, PointTarget >::reg_name_
std::string reg_name_
The registration method name.
Definition: registration.h:556
pcl::NormalDistributionsTransform2D::setGridCentre
virtual void setGridCentre(const Eigen::Vector2f &centre)
centre of the ndt grid (target coordinate system)
Definition: ndt_2d.h:94