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