KannalaBrandt8.h 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 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 "GeometricCamera.h"
  22. #include "TwoViewReconstruction.h"
  23. namespace ORB_SLAM3 {
  24. class KannalaBrandt8 : public GeometricCamera {
  25. friend class boost::serialization::access;
  26. template<class Archive>
  27. void serialize(Archive& ar, const unsigned int version)
  28. {
  29. ar & boost::serialization::base_object<GeometricCamera>(*this);
  30. ar & const_cast<float&>(precision);
  31. }
  32. public:
  33. KannalaBrandt8() : precision(1e-6) {
  34. mvParameters.resize(8);
  35. mnId=nNextId++;
  36. mnType = CAM_FISHEYE;
  37. }
  38. KannalaBrandt8(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), precision(1e-6), mvLappingArea(2,0) ,tvr(nullptr) {
  39. assert(mvParameters.size() == 8);
  40. mnId=nNextId++;
  41. mnType = CAM_FISHEYE;
  42. }
  43. KannalaBrandt8(const std::vector<float> _vParameters, const float _precision) : GeometricCamera(_vParameters),
  44. precision(_precision), mvLappingArea(2,0) {
  45. assert(mvParameters.size() == 8);
  46. mnId=nNextId++;
  47. mnType = CAM_FISHEYE;
  48. }
  49. KannalaBrandt8(KannalaBrandt8* pKannala) : GeometricCamera(pKannala->mvParameters), precision(pKannala->precision), mvLappingArea(2,0) ,tvr(nullptr) {
  50. assert(mvParameters.size() == 8);
  51. mnId=nNextId++;
  52. mnType = CAM_FISHEYE;
  53. }
  54. cv::Point2f project(const cv::Point3f &p3D);
  55. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  56. Eigen::Vector2f project(const Eigen::Vector3f & v3D);
  57. Eigen::Vector2f projectMat(const cv::Point3f& p3D);
  58. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  59. Eigen::Vector3f unprojectEig(const cv::Point2f &p2D);
  60. cv::Point3f unproject(const cv::Point2f &p2D);
  61. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  62. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  63. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  64. cv::Mat toK();
  65. Eigen::Matrix3f toK_();
  66. bool epipolarConstrain(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const Eigen::Matrix3f& R12, const Eigen::Vector3f& t12, const float sigmaLevel, const float unc);
  67. float TriangulateMatches(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const Eigen::Matrix3f& R12, const Eigen::Vector3f& t12, const float sigmaLevel, const float unc, Eigen::Vector3f& p3D);
  68. std::vector<int> mvLappingArea;
  69. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  70. Sophus::SE3f& Tcw1, Sophus::SE3f& Tcw2,
  71. const float sigmaLevel1, const float sigmaLevel2,
  72. Eigen::Vector3f& x3Dtriangulated);
  73. friend std::ostream& operator<<(std::ostream& os, const KannalaBrandt8& kb);
  74. friend std::istream& operator>>(std::istream& is, KannalaBrandt8& kb);
  75. float GetPrecision(){ return precision;}
  76. bool IsEqual(GeometricCamera* pCam);
  77. private:
  78. const float precision;
  79. //Parameters vector corresponds to
  80. //[fx, fy, cx, cy, k0, k1, k2, k3]
  81. TwoViewReconstruction* tvr;
  82. void Triangulate(const cv::Point2f &p1, const cv::Point2f &p2, const Eigen::Matrix<float,3,4> &Tcw1,
  83. const Eigen::Matrix<float,3,4> &Tcw2, Eigen::Vector3f &x3D);
  84. };
  85. }
  86. #endif //CAMERAMODELS_KANNALABRANDT8_H