Point Cloud Library (PCL) 1.13.0
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
46namespace 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 */
58template <typename PointSource, typename PointTarget>
59class 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
71public:
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 */
88 ~NormalDistributionsTransform2D() override = default;
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
143protected:
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
153 using Registration<PointSource, PointTarget>::reg_name_;
154 using Registration<PointSource, PointTarget>::target_;
155 using Registration<PointSource, PointTarget>::converged_;
156 using Registration<PointSource, PointTarget>::nr_iterations_;
157 using Registration<PointSource, PointTarget>::max_iterations_;
158 using Registration<PointSource, PointTarget>::transformation_epsilon_;
159 using Registration<PointSource, PointTarget>::transformation_rotation_epsilon_;
160 using Registration<PointSource, PointTarget>::transformation_;
161 using Registration<PointSource, PointTarget>::previous_transformation_;
162 using Registration<PointSource, PointTarget>::final_transformation_;
163 using Registration<PointSource, PointTarget>::update_visualizer_;
164 using Registration<PointSource, PointTarget>::indices_;
165
166 Eigen::Vector2f grid_centre_;
167 Eigen::Vector2f grid_step_;
168 Eigen::Vector2f grid_extent_;
169 Eigen::Vector3d newton_lambda_;
170
171public:
173};
174
175} // namespace pcl
176
177#include <pcl/registration/impl/ndt_2d.hpp>
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algor...
Definition: ndt_2d.h:59
virtual void setOptimizationStepSize(const double &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:122
virtual void setOptimizationStepSize(const Eigen::Vector3d &lambda)
NDT Newton optimisation step size parameter.
Definition: ndt_2d.h:138
~NormalDistributionsTransform2D() override=default
Empty destructor.
virtual void setGridStep(const Eigen::Vector2f &step)
Grid spacing (step) of the NDT grid.
Definition: ndt_2d.h:103
virtual void setGridExtent(const Eigen::Vector2f &extent)
NDT Grid extent (in either direction from the grid centre)
Definition: ndt_2d.h:112
virtual void setGridCentre(const Eigen::Vector2f &centre)
centre of the ndt grid (target coordinate system)
Definition: ndt_2d.h:94
Eigen::Vector3d newton_lambda_
Definition: ndt_2d.h:169
NormalDistributionsTransform2D()
Empty constructor.
Definition: ndt_2d.h:77
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:391
shared_ptr< NormalDistributionsTransform2D< PointSource, PointTarget > > Ptr
Definition: ndt_2d.h:72
shared_ptr< const NormalDistributionsTransform2D< PointSource, PointTarget > > ConstPtr
Definition: ndt_2d.h:74
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition: pcl_base.h:150
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
Definition: registration.h:585
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
Definition: registration.h:665
std::string reg_name_
The registration method name.
Definition: registration.h:560
Matrix4 transformation_
The transformation matrix estimated by the registration method.
Definition: registration.h:588
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
Definition: registration.h:570
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
Definition: registration.h:592
bool converged_
Holds internal convergence state, given user parameters.
Definition: registration.h:625
int max_iterations_
The maximum number of iterations the internal optimization should run for.
Definition: registration.h:575
double transformation_rotation_epsilon_
The maximum rotation difference between two consecutive transformations in order to consider converge...
Definition: registration.h:602
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:597
PointCloudTargetConstPtr target_
The input point cloud dataset target.
Definition: registration.h:581
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
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