MLPnPsolver.h 9.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. /******************************************************************************
  19. * Author: Steffen Urban *
  20. * Contact: urbste@gmail.com *
  21. * License: Copyright (c) 2016 Steffen Urban, ANU. All rights reserved. *
  22. * *
  23. * Redistribution and use in source and binary forms, with or without *
  24. * modification, are permitted provided that the following conditions *
  25. * are met: *
  26. * * Redistributions of source code must retain the above copyright *
  27. * notice, this list of conditions and the following disclaimer. *
  28. * * Redistributions in binary form must reproduce the above copyright *
  29. * notice, this list of conditions and the following disclaimer in the *
  30. * documentation and/or other materials provided with the distribution. *
  31. * * Neither the name of ANU nor the names of its contributors may be *
  32. * used to endorse or promote products derived from this software without *
  33. * specific prior written permission. *
  34. * *
  35. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"*
  36. * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
  37. * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE *
  38. * ARE DISCLAIMED. IN NO EVENT SHALL ANU OR THE CONTRIBUTORS BE LIABLE *
  39. * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL *
  40. * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR *
  41. * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
  42. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
  43. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY *
  44. * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF *
  45. * SUCH DAMAGE. *
  46. ******************************************************************************/
  47. #ifndef ORB_SLAM3_MLPNPSOLVER_H
  48. #define ORB_SLAM3_MLPNPSOLVER_H
  49. #include "MapPoint.h"
  50. #include "Frame.h"
  51. #include<Eigen/Dense>
  52. #include<Eigen/Sparse>
  53. namespace ORB_SLAM3{
  54. class MLPnPsolver {
  55. public:
  56. MLPnPsolver(const Frame &F, const vector<MapPoint*> &vpMapPointMatches);
  57. ~MLPnPsolver();
  58. void SetRansacParameters(double probability = 0.99, int minInliers = 8, int maxIterations = 300, int minSet = 6, float epsilon = 0.4,
  59. float th2 = 5.991);
  60. //Find metod is necessary?
  61. cv::Mat iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers);
  62. //Type definitions needed by the original code
  63. /** A 3-vector of unit length used to describe landmark observations/bearings
  64. * in camera frames (always expressed in camera frames)
  65. */
  66. typedef Eigen::Vector3d bearingVector_t;
  67. /** An array of bearing-vectors */
  68. typedef std::vector<bearingVector_t, Eigen::aligned_allocator<bearingVector_t> >
  69. bearingVectors_t;
  70. /** A 2-matrix containing the 2D covariance information of a bearing vector
  71. */
  72. typedef Eigen::Matrix2d cov2_mat_t;
  73. /** A 3-matrix containing the 3D covariance information of a bearing vector */
  74. typedef Eigen::Matrix3d cov3_mat_t;
  75. /** An array of 3D covariance matrices */
  76. typedef std::vector<cov3_mat_t, Eigen::aligned_allocator<cov3_mat_t> >
  77. cov3_mats_t;
  78. /** A 3-vector describing a point in 3D-space */
  79. typedef Eigen::Vector3d point_t;
  80. /** An array of 3D-points */
  81. typedef std::vector<point_t, Eigen::aligned_allocator<point_t> >
  82. points_t;
  83. /** A homogeneous 3-vector describing a point in 3D-space */
  84. typedef Eigen::Vector4d point4_t;
  85. /** An array of homogeneous 3D-points */
  86. typedef std::vector<point4_t, Eigen::aligned_allocator<point4_t> >
  87. points4_t;
  88. /** A 3-vector containing the rodrigues parameters of a rotation matrix */
  89. typedef Eigen::Vector3d rodrigues_t;
  90. /** A rotation matrix */
  91. typedef Eigen::Matrix3d rotation_t;
  92. /** A 3x4 transformation matrix containing rotation \f$ \mathbf{R} \f$ and
  93. * translation \f$ \mathbf{t} \f$ as follows:
  94. * \f$ \left( \begin{array}{cc} \mathbf{R} & \mathbf{t} \end{array} \right) \f$
  95. */
  96. typedef Eigen::Matrix<double,3,4> transformation_t;
  97. /** A 3-vector describing a translation/camera position */
  98. typedef Eigen::Vector3d translation_t;
  99. private:
  100. void CheckInliers();
  101. bool Refine();
  102. //Functions from de original MLPnP code
  103. /*
  104. * Computes the camera pose given 3D points coordinates (in the camera reference
  105. * system), the camera rays and (optionally) the covariance matrix of those camera rays.
  106. * Result is stored in solution
  107. */
  108. void computePose(
  109. const bearingVectors_t & f,
  110. const points_t & p,
  111. const cov3_mats_t & covMats,
  112. const std::vector<int>& indices,
  113. transformation_t & result);
  114. void mlpnp_gn(Eigen::VectorXd& x,
  115. const points_t& pts,
  116. const std::vector<Eigen::MatrixXd>& nullspaces,
  117. const Eigen::SparseMatrix<double> Kll,
  118. bool use_cov);
  119. void mlpnp_residuals_and_jacs(
  120. const Eigen::VectorXd& x,
  121. const points_t& pts,
  122. const std::vector<Eigen::MatrixXd>& nullspaces,
  123. Eigen::VectorXd& r,
  124. Eigen::MatrixXd& fjac,
  125. bool getJacs);
  126. void mlpnpJacs(
  127. const point_t& pt,
  128. const Eigen::Vector3d& nullspace_r,
  129. const Eigen::Vector3d& nullspace_s,
  130. const rodrigues_t& w,
  131. const translation_t& t,
  132. Eigen::MatrixXd& jacs);
  133. //Auxiliar methods
  134. /**
  135. * \brief Compute a rotation matrix from Rodrigues axis angle.
  136. *
  137. * \param[in] omega The Rodrigues-parameters of a rotation.
  138. * \return The 3x3 rotation matrix.
  139. */
  140. Eigen::Matrix3d rodrigues2rot(const Eigen::Vector3d & omega);
  141. /**
  142. * \brief Compute the Rodrigues-parameters of a rotation matrix.
  143. *
  144. * \param[in] R The 3x3 rotation matrix.
  145. * \return The Rodrigues-parameters.
  146. */
  147. Eigen::Vector3d rot2rodrigues(const Eigen::Matrix3d & R);
  148. //----------------------------------------------------
  149. //Fields of the solver
  150. //----------------------------------------------------
  151. vector<MapPoint*> mvpMapPointMatches;
  152. // 2D Points
  153. vector<cv::Point2f> mvP2D;
  154. //Substitued by bearing vectors
  155. bearingVectors_t mvBearingVecs;
  156. vector<float> mvSigma2;
  157. // 3D Points
  158. //vector<cv::Point3f> mvP3Dw;
  159. points_t mvP3Dw;
  160. // Index in Frame
  161. vector<size_t> mvKeyPointIndices;
  162. // Current Estimation
  163. double mRi[3][3];
  164. double mti[3];
  165. cv::Mat mTcwi;
  166. vector<bool> mvbInliersi;
  167. int mnInliersi;
  168. // Current Ransac State
  169. int mnIterations;
  170. vector<bool> mvbBestInliers;
  171. int mnBestInliers;
  172. cv::Mat mBestTcw;
  173. // Refined
  174. cv::Mat mRefinedTcw;
  175. vector<bool> mvbRefinedInliers;
  176. int mnRefinedInliers;
  177. // Number of Correspondences
  178. int N;
  179. // Indices for random selection [0 .. N-1]
  180. vector<size_t> mvAllIndices;
  181. // RANSAC probability
  182. double mRansacProb;
  183. // RANSAC min inliers
  184. int mRansacMinInliers;
  185. // RANSAC max iterations
  186. int mRansacMaxIts;
  187. // RANSAC expected inliers/total ratio
  188. float mRansacEpsilon;
  189. // RANSAC Threshold inlier/outlier. Max error e = dist(P1,T_12*P2)^2
  190. float mRansacTh;
  191. // RANSAC Minimun Set used at each iteration
  192. int mRansacMinSet;
  193. // Max square error associated with scale level. Max error = th*th*sigma(level)*sigma(level)
  194. vector<float> mvMaxError;
  195. GeometricCamera* mpCamera;
  196. };
  197. }
  198. #endif //ORB_SLAM3_MLPNPSOLVER_H