ndt_omp.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500
  1. /*
  2. * Software License Agreement (BSD License)
  3. *
  4. * Point Cloud Library (PCL) - www.pointclouds.org
  5. * Copyright (c) 2010-2012, 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. #ifndef PCL_REGISTRATION_NDT_OMP_H_
  41. #define PCL_REGISTRATION_NDT_OMP_H_
  42. #include <pcl/registration/registration.h>
  43. #include "voxel_grid_covariance_omp.h"
  44. #include <unsupported/Eigen/NonLinearOptimization>
  45. namespace pclomp
  46. {
  47. enum NeighborSearchMethod {
  48. KDTREE,
  49. DIRECT26,
  50. DIRECT7,
  51. DIRECT1
  52. };
  53. /** \brief A 3D Normal Distribution Transform registration implementation for point cloud data.
  54. * \note For more information please see
  55. * <b>Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform —
  56. * an Efficient Representation for Registration, Surface Analysis, and Loop Detection.
  57. * PhD thesis, Orebro University. Orebro Studies in Technology 36.</b>,
  58. * <b>More, J., and Thuente, D. (1994). Line Search Algorithm with Guaranteed Sufficient Decrease
  59. * In ACM Transactions on Mathematical Software.</b> and
  60. * Sun, W. and Yuan, Y, (2006) Optimization Theory and Methods: Nonlinear Programming. 89-100
  61. * \note Math refactored by Todor Stoyanov.
  62. * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific)
  63. */
  64. template<typename PointSource, typename PointTarget>
  65. class NormalDistributionsTransform : public pcl::Registration<PointSource, PointTarget>
  66. {
  67. protected:
  68. typedef typename pcl::Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
  69. typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
  70. typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
  71. typedef typename pcl::Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
  72. typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
  73. typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
  74. typedef pcl::PointIndices::Ptr PointIndicesPtr;
  75. typedef pcl::PointIndices::ConstPtr PointIndicesConstPtr;
  76. /** \brief Typename of searchable voxel grid containing mean and covariance. */
  77. typedef pclomp::VoxelGridCovariance<PointTarget> TargetGrid;
  78. /** \brief Typename of pointer to searchable voxel grid. */
  79. typedef TargetGrid* TargetGridPtr;
  80. /** \brief Typename of const pointer to searchable voxel grid. */
  81. typedef const TargetGrid* TargetGridConstPtr;
  82. /** \brief Typename of const pointer to searchable voxel grid leaf. */
  83. typedef typename TargetGrid::LeafConstPtr TargetGridLeafConstPtr;
  84. public:
  85. typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > Ptr;
  86. typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > ConstPtr;
  87. /** \brief Constructor.
  88. * Sets \ref outlier_ratio_ to 0.35, \ref step_size_ to 0.05 and \ref resolution_ to 1.0
  89. */
  90. NormalDistributionsTransform();
  91. /** \brief Empty destructor */
  92. virtual ~NormalDistributionsTransform() {}
  93. void setNumThreads(int n) {
  94. num_threads_ = n;
  95. }
  96. /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to).
  97. * \param[in] cloud the input point cloud target
  98. */
  99. inline void
  100. setInputTarget(const PointCloudTargetConstPtr &cloud)
  101. {
  102. pcl::Registration<PointSource, PointTarget>::setInputTarget(cloud);
  103. init();
  104. }
  105. /** \brief Set/change the voxel grid resolution.
  106. * \param[in] resolution side length of voxels
  107. */
  108. inline void
  109. setResolution(float resolution)
  110. {
  111. // Prevents unnessary voxel initiations
  112. if (resolution_ != resolution)
  113. {
  114. resolution_ = resolution;
  115. if (input_)
  116. init();
  117. }
  118. }
  119. /** \brief Get voxel grid resolution.
  120. * \return side length of voxels
  121. */
  122. inline float
  123. getResolution() const
  124. {
  125. return (resolution_);
  126. }
  127. /** \brief Get the newton line search maximum step length.
  128. * \return maximum step length
  129. */
  130. inline double
  131. getStepSize() const
  132. {
  133. return (step_size_);
  134. }
  135. /** \brief Set/change the newton line search maximum step length.
  136. * \param[in] step_size maximum step length
  137. */
  138. inline void
  139. setStepSize(double step_size)
  140. {
  141. step_size_ = step_size;
  142. }
  143. /** \brief Get the point cloud outlier ratio.
  144. * \return outlier ratio
  145. */
  146. inline double
  147. getOulierRatio() const
  148. {
  149. return (outlier_ratio_);
  150. }
  151. /** \brief Set/change the point cloud outlier ratio.
  152. * \param[in] outlier_ratio outlier ratio
  153. */
  154. inline void
  155. setOulierRatio(double outlier_ratio)
  156. {
  157. outlier_ratio_ = outlier_ratio;
  158. }
  159. inline void setNeighborhoodSearchMethod(NeighborSearchMethod method) {
  160. search_method = method;
  161. }
  162. /** \brief Get the registration alignment probability.
  163. * \return transformation probability
  164. */
  165. inline double
  166. getTransformationProbability() const
  167. {
  168. return (trans_probability_);
  169. }
  170. /** \brief Get the number of iterations required to calculate alignment.
  171. * \return final number of iterations
  172. */
  173. inline int
  174. getFinalNumIteration() const
  175. {
  176. return (nr_iterations_);
  177. }
  178. /** \brief Convert 6 element transformation vector to affine transformation.
  179. * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw]
  180. * \param[out] trans affine transform corresponding to given transfomation vector
  181. */
  182. static void
  183. convertTransform(const Eigen::Matrix<double, 6, 1> &x, Eigen::Affine3f &trans)
  184. {
  185. trans = Eigen::Translation<float, 3>(float(x(0)), float(x(1)), float(x(2))) *
  186. Eigen::AngleAxis<float>(float(x(3)), Eigen::Vector3f::UnitX()) *
  187. Eigen::AngleAxis<float>(float(x(4)), Eigen::Vector3f::UnitY()) *
  188. Eigen::AngleAxis<float>(float(x(5)), Eigen::Vector3f::UnitZ());
  189. }
  190. /** \brief Convert 6 element transformation vector to transformation matrix.
  191. * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw]
  192. * \param[out] trans 4x4 transformation matrix corresponding to given transfomation vector
  193. */
  194. static void
  195. convertTransform(const Eigen::Matrix<double, 6, 1> &x, Eigen::Matrix4f &trans)
  196. {
  197. Eigen::Affine3f _affine;
  198. convertTransform(x, _affine);
  199. trans = _affine.matrix();
  200. }
  201. // negative log likelihood function
  202. // lower is better
  203. double calculateScore(const PointCloudSource& cloud) const;
  204. protected:
  205. using pcl::Registration<PointSource, PointTarget>::reg_name_;
  206. using pcl::Registration<PointSource, PointTarget>::getClassName;
  207. using pcl::Registration<PointSource, PointTarget>::input_;
  208. using pcl::Registration<PointSource, PointTarget>::indices_;
  209. using pcl::Registration<PointSource, PointTarget>::target_;
  210. using pcl::Registration<PointSource, PointTarget>::nr_iterations_;
  211. using pcl::Registration<PointSource, PointTarget>::max_iterations_;
  212. using pcl::Registration<PointSource, PointTarget>::previous_transformation_;
  213. using pcl::Registration<PointSource, PointTarget>::final_transformation_;
  214. using pcl::Registration<PointSource, PointTarget>::transformation_;
  215. using pcl::Registration<PointSource, PointTarget>::transformation_epsilon_;
  216. using pcl::Registration<PointSource, PointTarget>::converged_;
  217. using pcl::Registration<PointSource, PointTarget>::corr_dist_threshold_;
  218. using pcl::Registration<PointSource, PointTarget>::inlier_threshold_;
  219. using pcl::Registration<PointSource, PointTarget>::update_visualizer_;
  220. /** \brief Estimate the transformation and returns the transformed source (input) as output.
  221. * \param[out] output the resultant input transfomed point cloud dataset
  222. */
  223. virtual void
  224. computeTransformation(PointCloudSource &output)
  225. {
  226. computeTransformation(output, Eigen::Matrix4f::Identity());
  227. }
  228. /** \brief Estimate the transformation and returns the transformed source (input) as output.
  229. * \param[out] output the resultant input transfomed point cloud dataset
  230. * \param[in] guess the initial gross estimation of the transformation
  231. */
  232. virtual void
  233. computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess);
  234. /** \brief Initiate covariance voxel structure. */
  235. void inline
  236. init()
  237. {
  238. target_cells_.setLeafSize(resolution_, resolution_, resolution_);
  239. target_cells_.setInputCloud(target_);
  240. // Initiate voxel structure.
  241. target_cells_.filter(true);
  242. }
  243. /** \brief Compute derivatives of probability function w.r.t. the transformation vector.
  244. * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
  245. * \param[out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector
  246. * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
  247. * \param[in] trans_cloud transformed point cloud
  248. * \param[in] p the current transform vector
  249. * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
  250. */
  251. double
  252. computeDerivatives(Eigen::Matrix<double, 6, 1> &score_gradient,
  253. Eigen::Matrix<double, 6, 6> &hessian,
  254. PointCloudSource &trans_cloud,
  255. Eigen::Matrix<double, 6, 1> &p,
  256. bool compute_hessian = true);
  257. /** \brief Compute individual point contirbutions to derivatives of probability function w.r.t. the transformation vector.
  258. * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
  259. * \param[in,out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector
  260. * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
  261. * \param[in] x_trans transformed point minus mean of occupied covariance voxel
  262. * \param[in] c_inv covariance of occupied covariance voxel
  263. * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
  264. */
  265. double
  266. updateDerivatives(Eigen::Matrix<double, 6, 1> &score_gradient,
  267. Eigen::Matrix<double, 6, 6> &hessian,
  268. const Eigen::Matrix<float, 4, 6> &point_gradient_,
  269. const Eigen::Matrix<float, 24, 6> &point_hessian_,
  270. const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv,
  271. bool compute_hessian = true) const;
  272. /** \brief Precompute anglular components of derivatives.
  273. * \note Equation 6.19 and 6.21 [Magnusson 2009].
  274. * \param[in] p the current transform vector
  275. * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
  276. */
  277. void
  278. computeAngleDerivatives(Eigen::Matrix<double, 6, 1> &p, bool compute_hessian = true);
  279. /** \brief Compute point derivatives.
  280. * \note Equation 6.18-21 [Magnusson 2009].
  281. * \param[in] x point from the input cloud
  282. * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
  283. */
  284. void
  285. computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix<double, 3, 6>& point_gradient_, Eigen::Matrix<double, 18, 6>& point_hessian_, bool compute_hessian = true) const;
  286. void
  287. computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix<float, 4, 6>& point_gradient_, Eigen::Matrix<float, 24, 6>& point_hessian_, bool compute_hessian = true) const;
  288. /** \brief Compute hessian of probability function w.r.t. the transformation vector.
  289. * \note Equation 6.13 [Magnusson 2009].
  290. * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
  291. * \param[in] trans_cloud transformed point cloud
  292. * \param[in] p the current transform vector
  293. */
  294. void
  295. computeHessian(Eigen::Matrix<double, 6, 6> &hessian,
  296. PointCloudSource &trans_cloud,
  297. Eigen::Matrix<double, 6, 1> &p);
  298. /** \brief Compute individual point contirbutions to hessian of probability function w.r.t. the transformation vector.
  299. * \note Equation 6.13 [Magnusson 2009].
  300. * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
  301. * \param[in] x_trans transformed point minus mean of occupied covariance voxel
  302. * \param[in] c_inv covariance of occupied covariance voxel
  303. */
  304. void
  305. updateHessian(Eigen::Matrix<double, 6, 6> &hessian,
  306. const Eigen::Matrix<double, 3, 6> &point_gradient_,
  307. const Eigen::Matrix<double, 18, 6> &point_hessian_,
  308. const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv) const;
  309. /** \brief Compute line search step length and update transform and probability derivatives using More-Thuente method.
  310. * \note Search Algorithm [More, Thuente 1994]
  311. * \param[in] x initial transformation vector, \f$ x \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \vec{p} \f$ in Algorithm 2 [Magnusson 2009]
  312. * \param[in] step_dir descent direction, \f$ p \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in Algorithm 2 [Magnusson 2009]
  313. * \param[in] step_init initial step length estimate, \f$ \alpha_0 \f$ in Moore-Thuente (1994) and the noramal of \f$ \delta \vec{p} \f$ in Algorithm 2 [Magnusson 2009]
  314. * \param[in] step_max maximum step length, \f$ \alpha_max \f$ in Moore-Thuente (1994)
  315. * \param[in] step_min minimum step length, \f$ \alpha_min \f$ in Moore-Thuente (1994)
  316. * \param[out] score final score function value, \f$ f(x + \alpha p) \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ score \f$ in Algorithm 2 [Magnusson 2009]
  317. * \param[in,out] score_gradient gradient of score function w.r.t. transformation vector, \f$ f'(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ \vec{g} \f$ in Algorithm 2 [Magnusson 2009]
  318. * \param[out] hessian hessian of score function w.r.t. transformation vector, \f$ f''(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ H \f$ in Algorithm 2 [Magnusson 2009]
  319. * \param[in,out] trans_cloud transformed point cloud, \f$ X \f$ transformed by \f$ T(\vec{p},\vec{x}) \f$ in Algorithm 2 [Magnusson 2009]
  320. * \return final step length
  321. */
  322. double
  323. computeStepLengthMT(const Eigen::Matrix<double, 6, 1> &x,
  324. Eigen::Matrix<double, 6, 1> &step_dir,
  325. double step_init,
  326. double step_max, double step_min,
  327. double &score,
  328. Eigen::Matrix<double, 6, 1> &score_gradient,
  329. Eigen::Matrix<double, 6, 6> &hessian,
  330. PointCloudSource &trans_cloud);
  331. /** \brief Update interval of possible step lengths for More-Thuente method, \f$ I \f$ in More-Thuente (1994)
  332. * \note Updating Algorithm until some value satifies \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$
  333. * and Modified Updating Algorithm from then on [More, Thuente 1994].
  334. * \param[in,out] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994)
  335. * \param[in,out] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_l) \f$ for Update Algorithm and \f$ \phi(\alpha_l) \f$ for Modified Update Algorithm
  336. * \param[in,out] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_l) \f$ for Update Algorithm and \f$ \phi'(\alpha_l) \f$ for Modified Update Algorithm
  337. * \param[in,out] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994)
  338. * \param[in,out] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_u) \f$ for Update Algorithm and \f$ \phi(\alpha_u) \f$ for Modified Update Algorithm
  339. * \param[in,out] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_u) \f$ for Update Algorithm and \f$ \phi'(\alpha_u) \f$ for Modified Update Algorithm
  340. * \param[in] a_t trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994)
  341. * \param[in] f_t value at trial value, \f$ f_t \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_t) \f$ for Update Algorithm and \f$ \phi(\alpha_t) \f$ for Modified Update Algorithm
  342. * \param[in] g_t derivative at trial value, \f$ g_t \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_t) \f$ for Update Algorithm and \f$ \phi'(\alpha_t) \f$ for Modified Update Algorithm
  343. * \return if interval converges
  344. */
  345. bool
  346. updateIntervalMT(double &a_l, double &f_l, double &g_l,
  347. double &a_u, double &f_u, double &g_u,
  348. double a_t, double f_t, double g_t);
  349. /** \brief Select new trial value for More-Thuente method.
  350. * \note Trial Value Selection [More, Thuente 1994], \f$ \psi(\alpha_k) \f$ is used for \f$ f_k \f$ and \f$ g_k \f$
  351. * until some value satifies the test \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$
  352. * then \f$ \phi(\alpha_k) \f$ is used from then on.
  353. * \note Interpolation Minimizer equations from Optimization Theory and Methods: Nonlinear Programming By Wenyu Sun, Ya-xiang Yuan (89-100).
  354. * \param[in] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994)
  355. * \param[in] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994)
  356. * \param[in] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994)
  357. * \param[in] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994)
  358. * \param[in] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994)
  359. * \param[in] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994)
  360. * \param[in] a_t previous trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994)
  361. * \param[in] f_t value at previous trial value, \f$ f_t \f$ in Moore-Thuente (1994)
  362. * \param[in] g_t derivative at previous trial value, \f$ g_t \f$ in Moore-Thuente (1994)
  363. * \return new trial value
  364. */
  365. double
  366. trialValueSelectionMT(double a_l, double f_l, double g_l,
  367. double a_u, double f_u, double g_u,
  368. double a_t, double f_t, double g_t);
  369. /** \brief Auxilary function used to determin endpoints of More-Thuente interval.
  370. * \note \f$ \psi(\alpha) \f$ in Equation 1.6 (Moore, Thuente 1994)
  371. * \param[in] a the step length, \f$ \alpha \f$ in More-Thuente (1994)
  372. * \param[in] f_a function value at step length a, \f$ \phi(\alpha) \f$ in More-Thuente (1994)
  373. * \param[in] f_0 initial function value, \f$ \phi(0) \f$ in Moore-Thuente (1994)
  374. * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994)
  375. * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994]
  376. * \return sufficent decrease value
  377. */
  378. inline double
  379. auxilaryFunction_PsiMT(double a, double f_a, double f_0, double g_0, double mu = 1.e-4)
  380. {
  381. return (f_a - f_0 - mu * g_0 * a);
  382. }
  383. /** \brief Auxilary function derivative used to determin endpoints of More-Thuente interval.
  384. * \note \f$ \psi'(\alpha) \f$, derivative of Equation 1.6 (Moore, Thuente 1994)
  385. * \param[in] g_a function gradient at step length a, \f$ \phi'(\alpha) \f$ in More-Thuente (1994)
  386. * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994)
  387. * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994]
  388. * \return sufficent decrease derivative
  389. */
  390. inline double
  391. auxilaryFunction_dPsiMT(double g_a, double g_0, double mu = 1.e-4)
  392. {
  393. return (g_a - mu * g_0);
  394. }
  395. /** \brief The voxel grid generated from target cloud containing point means and covariances. */
  396. TargetGrid target_cells_;
  397. //double fitness_epsilon_;
  398. /** \brief The side length of voxels. */
  399. float resolution_;
  400. /** \brief The maximum step length. */
  401. double step_size_;
  402. /** \brief The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009]. */
  403. double outlier_ratio_;
  404. /** \brief The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009]. */
  405. double gauss_d1_, gauss_d2_, gauss_d3_;
  406. /** \brief The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009]. */
  407. double trans_probability_;
  408. /** \brief Precomputed Angular Gradient
  409. *
  410. * The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009].
  411. */
  412. Eigen::Vector3d j_ang_a_, j_ang_b_, j_ang_c_, j_ang_d_, j_ang_e_, j_ang_f_, j_ang_g_, j_ang_h_;
  413. Eigen::Matrix<float, 8, 4> j_ang;
  414. /** \brief Precomputed Angular Hessian
  415. *
  416. * The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009].
  417. */
  418. Eigen::Vector3d h_ang_a2_, h_ang_a3_,
  419. h_ang_b2_, h_ang_b3_,
  420. h_ang_c2_, h_ang_c3_,
  421. h_ang_d1_, h_ang_d2_, h_ang_d3_,
  422. h_ang_e1_, h_ang_e2_, h_ang_e3_,
  423. h_ang_f1_, h_ang_f2_, h_ang_f3_;
  424. Eigen::Matrix<float, 16, 4> h_ang;
  425. /** \brief The first order derivative of the transformation of a point w.r.t. the transform vector, \f$ J_E \f$ in Equation 6.18 [Magnusson 2009]. */
  426. // Eigen::Matrix<double, 3, 6> point_gradient_;
  427. /** \brief The second order derivative of the transformation of a point w.r.t. the transform vector, \f$ H_E \f$ in Equation 6.20 [Magnusson 2009]. */
  428. // Eigen::Matrix<double, 18, 6> point_hessian_;
  429. int num_threads_;
  430. public:
  431. NeighborSearchMethod search_method;
  432. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  433. };
  434. }
  435. #endif // PCL_REGISTRATION_NDT_H_