Apollo 10.0
自动驾驶开放平台
ndt_solver.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16/*
17 * Software License Agreement (BSD License)
18 *
19 * Point Cloud Library (PCL) - www.pointclouds.org
20 * Copyright (c) 2010-2012, Willow Garage, Inc.
21 * Copyright (c) 2012-, Open Perception, Inc.
22 *
23 * All rights reserved.
24 *
25 * Redistribution and use in source and binary forms, with or without
26 * modification, are permitted provided that the following conditions
27 * are met:
28 *
29 * * Redistributions of source code must retain the above copyright
30 * notice, this list of conditions and the following disclaimer.
31 * * Redistributions in binary form must reproduce the above
32 * copyright notice, this list of conditions and the following
33 * disclaimer in the documentation and/or other materials provided
34 * with the distribution.
35 * * Neither the name of the copyright holder(s) nor the names of its
36 * contributors may be used to endorse or promote products derived
37 * from this software without specific prior written permission.
38 *
39 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
40 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
41 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
42 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
43 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
44 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
45 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
46 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
47 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
48 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
49 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
50 * POSSIBILITY OF SUCH DAMAGE.
51 *
52 * $Id$
53 *
54 */
55
56#pragma once
57
58#include <limits>
59#include <vector>
60
61#include "pcl/registration/registration.h"
62#include "unsupported/Eigen/NonLinearOptimization"
63
64#include "cyber/common/log.h"
67
68namespace apollo {
69namespace localization {
70namespace ndt {
71
72template <typename PointSource, typename PointTarget>
74 protected:
76 typedef typename pcl::PointCloud<PointSource> PointCloudSource;
77 typedef typename boost::shared_ptr<PointCloudSource> PointCloudSourcePtr;
78 typedef boost::shared_ptr<const PointCloudSource> PointCloudSourceConstPtr;
79
81 typedef typename pcl::PointCloud<PointTarget> PointCloudTarget;
82 typedef boost::shared_ptr<const PointCloudTarget> PointCloudTargetConstPtr;
83
89
91 typedef pcl::search::KdTree<PointTarget> KdTree;
92 typedef typename pcl::search::KdTree<PointTarget>::Ptr KdTreePtr;
93
94 public:
96 typedef boost::shared_ptr<
99 typedef boost::shared_ptr<
102
105
108 target_.reset();
109 input_.reset();
110 }
111
113 inline void SetInputTarget(const std::vector<Leaf> &cell_leaf,
114 const PointCloudTargetConstPtr &cloud) {
115 if (cell_leaf.empty()) {
116 AWARN << "Input leaf is empty.";
117 return;
118 }
119 if (cloud->points.empty()) {
120 AWARN << "Input target is empty.";
121 return;
122 }
123
124 target_ = cloud;
127 target_cells_.filter(cell_leaf, true);
128 }
129
131 inline void SetInputSource(const PointCloudTargetConstPtr &cloud) {
132 if (cloud->points.empty()) {
133 AWARN << "Input source is empty.";
134 return;
135 }
136 input_ = cloud;
137 }
138
140 inline void SetResolution(float resolution) {
141 // Prevents unnessary voxel initiations
142 if (resolution_ != resolution) {
143 resolution_ = resolution;
144 }
145 AINFO << "NDT Resolution: " << resolution_;
146 }
147
149 inline float GetResolution() const { return resolution_; }
150
154 inline double GetStepSize() const { return step_size_; }
155
159 inline void SetStepSize(double step_size) { step_size_ = step_size; }
160
162 inline double GetOulierRatio() const { return outlier_ratio_; }
163
165 inline void SetOulierRatio(double outlier_ratio) {
166 outlier_ratio_ = outlier_ratio;
167 }
168
170 inline double GetTransformationProbability() const {
171 return trans_probability_;
172 }
173
175 inline int GetFinalNumIteration() const { return nr_iterations_; }
176
178 inline bool HasConverged() const { return converged_; }
179
182 inline Eigen::Matrix4f GetFinalTransformation() const {
184 }
185
188 inline void SetMaximumIterations(int nr_iterations) {
189 max_iterations_ = nr_iterations;
190 }
191
194 inline void SetTransformationEpsilon(double epsilon) {
195 transformation_epsilon_ = epsilon;
196 }
197
199 static void ConvertTransform(const Eigen::Matrix<double, 6, 1> &x,
200 Eigen::Affine3f *trans) {
201 *trans = Eigen::Translation<float, 3>(static_cast<float>(x(0)),
202 static_cast<float>(x(1)),
203 static_cast<float>(x(2))) *
204 Eigen::AngleAxis<float>(static_cast<float>(x(3)),
205 Eigen::Vector3f::UnitX()) *
206 Eigen::AngleAxis<float>(static_cast<float>(x(4)),
207 Eigen::Vector3f::UnitY()) *
208 Eigen::AngleAxis<float>(static_cast<float>(x(5)),
209 Eigen::Vector3f::UnitZ());
210 }
211
213 static void ConvertTransform(const Eigen::Matrix<double, 6, 1> &x,
214 Eigen::Matrix4f *trans) {
215 Eigen::Affine3f _affine;
216 ConvertTransform(x, &_affine);
217 *trans = _affine.matrix();
218 }
219
221 void GetGridPointCloud(pcl::PointCloud<pcl::PointXYZ> *cell_cloud) {
222 target_cells_.GetDisplayCloud(*cell_cloud);
223 }
224
226 inline void SetLeftTopCorner(const Eigen::Vector3d &left_top_corner) {
227 target_cells_.SetMapLeftTopCorner(left_top_corner);
228 }
229
231 double GetFitnessScore(double max_range = std::numeric_limits<double>::max());
232
235 void Align(PointCloudSourcePtr output, const Eigen::Matrix4f &guess);
236
237 protected:
241 ComputeTransformation(output, Eigen::Matrix4f::Identity());
242 }
243
247 const Eigen::Matrix4f &guess);
248
251 double ComputeDerivatives(Eigen::Matrix<double, 6, 1> *score_gradient,
252 Eigen::Matrix<double, 6, 6> *hessian,
253 PointCloudSourcePtr trans_cloud,
254 Eigen::Matrix<double, 6, 1> *p,
255 bool ComputeHessian = true);
256
259 double UpdateDerivatives(Eigen::Matrix<double, 6, 1> *score_gradient,
260 Eigen::Matrix<double, 6, 6> *hessian,
261 const Eigen::Vector3d &x_trans,
262 const Eigen::Matrix3d &c_inv,
263 bool ComputeHessian = true);
264
266 void ComputeAngleDerivatives(const Eigen::Matrix<double, 6, 1> &p,
267 bool ComputeHessian = true);
268
270 void ComputePointDerivatives(const Eigen::Vector3d &x,
271 bool ComputeHessian = true);
272
275 void ComputeHessian(Eigen::Matrix<double, 6, 6> *hessian,
276 const PointCloudSource &trans_cloud,
277 Eigen::Matrix<double, 6, 1> *p);
278
281 void UpdateHessian(Eigen::Matrix<double, 6, 6> *hessian,
282 const Eigen::Vector3d &x_trans,
283 const Eigen::Matrix3d &c_inv);
284
287 double ComputeStepLengthMt(const Eigen::Matrix<double, 6, 1> &x,
288 Eigen::Matrix<double, 6, 1> *step_dir,
289 double step_init, double step_max, double step_min,
290 double *score,
291 Eigen::Matrix<double, 6, 1> *score_gradient,
292 Eigen::Matrix<double, 6, 6> *hessian,
293 PointCloudSourcePtr trans_cloud);
294
296 bool UpdateIntervalMt(double *a_l, double *f_l, double *g_l, double *a_u,
297 double *f_u, double *g_u, double a_t, double f_t,
298 double g_t);
299
301 double TrialValueSelectionMt(double a_l, double f_l, double g_l, double a_u,
302 double f_u, double g_u, double a_t, double f_t,
303 double g_t);
304
307 inline double AuxilaryFunctionPsimt(double a, double f_a, double f_0,
308 double g_0, double mu = 1.e-4) {
309 return (f_a - f_0 - mu * g_0 * a);
310 }
311
314 inline double AuxilaryFunctionDpsimt(double g_a, double g_0,
315 double mu = 1.e-4) {
316 return (g_a - mu * g_0);
317 }
318
319 protected:
327
330
336 Eigen::Matrix4f final_transformation_;
337 Eigen::Matrix4f transformation_;
338
356
368 Eigen::Matrix<double, 3, 6> point_gradient_;
371 Eigen::Matrix<double, 18, 6> point_hessian_;
372
373 public:
374 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
375};
376
377} // namespace ndt
378} // namespace localization
379} // namespace apollo
380
381#include "modules/localization/ndt/ndt_locator/ndt_solver.hpp"
pcl::search::KdTree< PointTarget >::Ptr KdTreePtr
Definition ndt_solver.h:92
void SetStepSize(double step_size)
Set/change the newton line search maximum step length.
Definition ndt_solver.h:159
void SetResolution(float resolution)
Set/change the voxel grid resolution.
Definition ndt_solver.h:140
PointCloudSourceConstPtr input_
A pointer of input source point cloud.
Definition ndt_solver.h:329
Eigen::Vector3d j_ang_a_
The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6....
Definition ndt_solver.h:359
Eigen::Matrix4f GetFinalTransformation() const
Get the final transformation matrix estimated by the registration method.
Definition ndt_solver.h:182
Eigen::Matrix< double, 18, 6 > point_hessian_
The second order derivative of the transformation of a point w.r.t.
Definition ndt_solver.h:371
double GetFitnessScore(double max_range=std::numeric_limits< double >::max())
Obtain the Euclidean fitness score.
bool HasConverged() const
Return the state of convergence after the last align run.
Definition ndt_solver.h:178
void GetGridPointCloud(pcl::PointCloud< pcl::PointXYZ > *cell_cloud)
Obtain probability point cloud.
Definition ndt_solver.h:221
double GetTransformationProbability() const
Get the registration alignment probability.
Definition ndt_solver.h:170
void SetMaximumIterations(int nr_iterations)
Set the maximum number of iterations the internal optimization should run for.
Definition ndt_solver.h:188
VoxelGridCovariance< PointTarget > TargetGrid
Typename of searchable voxel grid containing mean and covariance.
Definition ndt_solver.h:85
boost::shared_ptr< const PointCloudSource > PointCloudSourceConstPtr
Definition ndt_solver.h:78
int GetFinalNumIteration() const
Get the number of iterations required to calculate alignment.
Definition ndt_solver.h:175
Eigen::Matrix< double, 3, 6 > point_gradient_
The first order derivative of the transformation of a point w.r.t.
Definition ndt_solver.h:368
boost::shared_ptr< const PointCloudTarget > PointCloudTargetConstPtr
Definition ndt_solver.h:82
static void ConvertTransform(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix4f *trans)
Convert 6 element transformation vector to transformation matrix.
Definition ndt_solver.h:213
pcl::PointCloud< PointSource > PointCloudSource
Typename of source point.
Definition ndt_solver.h:76
void ComputeTransformation(PointCloudSourcePtr output, const Eigen::Matrix4f &guess)
Estimate the transformation and returns the transformed source (input) as output.
void SetInputTarget(const std::vector< Leaf > &cell_leaf, const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target.
Definition ndt_solver.h:113
boost::shared_ptr< PointCloudSource > PointCloudSourcePtr
Definition ndt_solver.h:77
void SetLeftTopCorner(const Eigen::Vector3d &left_top_corner)
Set left top corner of target point cloud.
Definition ndt_solver.h:226
void SetOulierRatio(double outlier_ratio)
Set/change the point cloud outlier ratio.
Definition ndt_solver.h:165
Eigen::Vector3d h_ang_a2_
The precomputed angular derivatives for the hessian of a transformation vector, Equation 6....
Definition ndt_solver.h:363
bool UpdateIntervalMt(double *a_l, double *f_l, double *g_l, double *a_u, double *f_u, double *g_u, double a_t, double f_t, double g_t)
Update interval of possible step lengths for More-Thuente method.
float GetResolution() const
Get voxel grid resolution.
Definition ndt_solver.h:149
double gauss_d1_
The normalization constants used fit the point distribution to a normal distribution,...
Definition ndt_solver.h:352
static void ConvertTransform(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Affine3f *trans)
Convert 6 element transformation vector to affine transformation.
Definition ndt_solver.h:199
double transformation_epsilon_
Transformation epsilon parameter.
Definition ndt_solver.h:342
void ComputeTransformation(PointCloudSourcePtr output)
Estimate the transformation and returns the transformed source (input) as output.
Definition ndt_solver.h:240
void ComputePointDerivatives(const Eigen::Vector3d &x, bool ComputeHessian=true)
Compute point derivatives.
boost::shared_ptr< const NormalDistributionsTransform< PointSource, PointTarget > > ConstPtr
Definition ndt_solver.h:101
void ComputeHessian(Eigen::Matrix< double, 6, 6 > *hessian, const PointCloudSource &trans_cloud, Eigen::Matrix< double, 6, 1 > *p)
Compute hessian of probability function w.r.t.
Eigen::Matrix4f previous_transformation_
transformations.
Definition ndt_solver.h:335
void SetInputSource(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target.
Definition ndt_solver.h:131
pcl::PointCloud< PointTarget > PointCloudTarget
Typename of target point.
Definition ndt_solver.h:81
void Align(PointCloudSourcePtr output, const Eigen::Matrix4f &guess)
Call the registration algorithm which estimates the transformation and returns the transformed source...
double UpdateDerivatives(Eigen::Matrix< double, 6, 1 > *score_gradient, Eigen::Matrix< double, 6, 6 > *hessian, const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv, bool ComputeHessian=true)
Compute individual point contributions to derivatives of probability function w.r....
double TrialValueSelectionMt(double a_l, double f_l, double g_l, double a_u, double f_u, double g_u, double a_t, double f_t, double g_t)
Select new trial value for More-Thuente method.
double trans_probability_
The probability score of the transform applied to the input cloud, Equation 6.9 and 6....
Definition ndt_solver.h:355
double GetOulierRatio() const
Get the point cloud outlier ratio.
Definition ndt_solver.h:162
double GetStepSize() const
Get the newton line search maximum step length.
Definition ndt_solver.h:154
void UpdateHessian(Eigen::Matrix< double, 6, 6 > *hessian, const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv)
Compute individual point contributions to hessian of probability function.
void ComputeAngleDerivatives(const Eigen::Matrix< double, 6, 1 > &p, bool ComputeHessian=true)
Precompute anglular components of derivatives.
double AuxilaryFunctionDpsimt(double g_a, double g_0, double mu=1.e-4)
Auxiliary function derivative used to determine endpoints of More-Thuente interval.
Definition ndt_solver.h:314
boost::shared_ptr< NormalDistributionsTransform< PointSource, PointTarget > > Ptr
Typedef shared pointer.
Definition ndt_solver.h:98
TargetGrid target_cells_
The voxel grid generated from target cloud containing point means and covariances.
Definition ndt_solver.h:326
double outlier_ratio_
The ratio of outliers of points w.r.t.
Definition ndt_solver.h:349
pcl::search::KdTree< PointTarget > KdTree
Typename of KD-Tree.
Definition ndt_solver.h:91
double AuxilaryFunctionPsimt(double a, double f_a, double f_0, double g_0, double mu=1.e-4)
Auxiliary function used to determine endpoints of More-Thuente interval.
Definition ndt_solver.h:307
void SetTransformationEpsilon(double epsilon)
Set the transformation epsilon (maximum allowable difference between two consecutive transformations.
Definition ndt_solver.h:194
double ComputeDerivatives(Eigen::Matrix< double, 6, 1 > *score_gradient, Eigen::Matrix< double, 6, 6 > *hessian, PointCloudSourcePtr trans_cloud, Eigen::Matrix< double, 6, 1 > *p, bool ComputeHessian=true)
Compute derivatives of probability function w.r.t.
double ComputeStepLengthMt(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix< double, 6, 1 > *step_dir, double step_init, double step_max, double step_min, double *score, Eigen::Matrix< double, 6, 1 > *score_gradient, Eigen::Matrix< double, 6, 6 > *hessian, PointCloudSourcePtr trans_cloud)
Compute line search step length and update transform and probability derivatives.
PointCloudTargetConstPtr target_
A pointer of input target point cloud.
Definition ndt_solver.h:321
KdTreePtr target_tree_
A pointer to the spatial search object.
Definition ndt_solver.h:323
A searchable voxel structure containing the mean and covariance of the data.
void SetMapLeftTopCorner(const Eigen::Vector3d &left_top_corner)
void SetInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
void SetVoxelGridResolution(float lx, float ly, float lz)
void filter(const std::vector< Leaf > &cell_leaf, bool searchable=true)
Initializes voxel structure.
void GetDisplayCloud(pcl::PointCloud< pcl::PointXYZ > *cell_cloud)
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
class register implement
Definition arena_queue.h:37
Simple structure to hold a centroid, covarince and the number of points in a leaf.