KannalaBrandt8.h 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116
  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. #ifndef CAMERAMODELS_KANNALABRANDT8_H
  19. #define CAMERAMODELS_KANNALABRANDT8_H
  20. #include <assert.h>
  21. #include <vector>
  22. #include <opencv2/core/core.hpp>
  23. #include <boost/serialization/serialization.hpp>
  24. #include <boost/serialization/base_object.hpp>
  25. #include <boost/serialization/vector.hpp>
  26. #include "GeometricCamera.h"
  27. #include "TwoViewReconstruction.h"
  28. namespace ORB_SLAM3 {
  29. class KannalaBrandt8 final : public GeometricCamera {
  30. public:
  31. KannalaBrandt8() : precision(1e-6) {
  32. mvParameters.resize(8);
  33. mnId=nNextId++;
  34. mnType = CAM_FISHEYE;
  35. }
  36. KannalaBrandt8(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), precision(1e-6), mvLappingArea(2,0) ,tvr(nullptr) {
  37. assert(mvParameters.size() == 8);
  38. mnId=nNextId++;
  39. mnType = CAM_FISHEYE;
  40. }
  41. KannalaBrandt8(const std::vector<float> _vParameters, const float _precision) : GeometricCamera(_vParameters),
  42. precision(_precision), mvLappingArea(2,0) {
  43. assert(mvParameters.size() == 8);
  44. mnId=nNextId++;
  45. mnType = CAM_FISHEYE;
  46. }
  47. KannalaBrandt8(KannalaBrandt8* pKannala) : GeometricCamera(pKannala->mvParameters), precision(pKannala->precision), mvLappingArea(2,0) ,tvr(nullptr) {
  48. assert(mvParameters.size() == 8);
  49. mnId=nNextId++;
  50. mnType = CAM_FISHEYE;
  51. }
  52. cv::Point2f project(const cv::Point3f &p3D);
  53. cv::Point2f project(const cv::Matx31f &m3D);
  54. cv::Point2f project(const cv::Mat& m3D);
  55. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  56. cv::Mat projectMat(const cv::Point3f& p3D);
  57. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  58. cv::Point3f unproject(const cv::Point2f &p2D);
  59. cv::Mat unprojectMat(const cv::Point2f &p2D);
  60. cv::Matx31f unprojectMat_(const cv::Point2f &p2D);
  61. cv::Mat projectJac(const cv::Point3f &p3D);
  62. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  63. cv::Mat unprojectJac(const cv::Point2f &p2D);
  64. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  65. cv::Mat &R21, cv::Mat &t21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  66. cv::Mat toK();
  67. cv::Matx33f toK_();
  68. bool epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc);
  69. bool epipolarConstrain_(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Matx33f& R12, const cv::Matx31f& t12, const float sigmaLevel, const float unc);
  70. float TriangulateMatches(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc, cv::Mat& p3D);
  71. float TriangulateMatches_(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Matx33f& R12, const cv::Matx31f& t12, const float sigmaLevel, const float unc, cv::Matx31f& p3D);
  72. std::vector<int> mvLappingArea;
  73. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  74. cv::Mat& Tcw1, cv::Mat& Tcw2,
  75. const float sigmaLevel1, const float sigmaLevel2,
  76. cv::Mat& x3Dtriangulated);
  77. friend std::ostream& operator<<(std::ostream& os, const KannalaBrandt8& kb);
  78. friend std::istream& operator>>(std::istream& is, KannalaBrandt8& kb);
  79. private:
  80. const float precision;
  81. //Parameters vector corresponds to
  82. //[fx, fy, cx, cy, k0, k1, k2, k3]
  83. TwoViewReconstruction* tvr;
  84. void Triangulate(const cv::Point2f &p1, const cv::Point2f &p2, const cv::Mat &Tcw1, const cv::Mat &Tcw2,cv::Mat &x3D);
  85. void Triangulate_(const cv::Point2f &p1, const cv::Point2f &p2, const cv::Matx44f &Tcw1, const cv::Matx44f &Tcw2,cv::Matx31f &x3D);
  86. };
  87. }
  88. //BOOST_CLASS_EXPORT_KEY(ORBSLAM2::KannalaBrandt8)
  89. #endif //CAMERAMODELS_KANNALABRANDT8_H