KannalaBrandt8.h 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118
  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. friend class boost::serialization::access;
  31. template<class Archive>
  32. void serialize(Archive& ar, const unsigned int version)
  33. {
  34. ar & boost::serialization::base_object<GeometricCamera>(*this);
  35. ar & const_cast<float&>(precision);
  36. }
  37. public:
  38. KannalaBrandt8() : precision(1e-6) {
  39. mvParameters.resize(8);
  40. mnId=nNextId++;
  41. mnType = CAM_FISHEYE;
  42. }
  43. KannalaBrandt8(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), precision(1e-6), mvLappingArea(2,0) ,tvr(nullptr) {
  44. assert(mvParameters.size() == 8);
  45. mnId=nNextId++;
  46. mnType = CAM_FISHEYE;
  47. }
  48. KannalaBrandt8(const std::vector<float> _vParameters, const float _precision) : GeometricCamera(_vParameters),
  49. precision(_precision), mvLappingArea(2,0) {
  50. assert(mvParameters.size() == 8);
  51. mnId=nNextId++;
  52. mnType = CAM_FISHEYE;
  53. }
  54. KannalaBrandt8(KannalaBrandt8* pKannala) : GeometricCamera(pKannala->mvParameters), precision(pKannala->precision), mvLappingArea(2,0) ,tvr(nullptr) {
  55. assert(mvParameters.size() == 8);
  56. mnId=nNextId++;
  57. mnType = CAM_FISHEYE;
  58. }
  59. cv::Point2f project(const cv::Point3f &p3D);
  60. cv::Point2f project(const cv::Mat& m3D);
  61. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  62. cv::Mat projectMat(const cv::Point3f& p3D);
  63. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  64. cv::Point3f unproject(const cv::Point2f &p2D);
  65. cv::Mat unprojectMat(const cv::Point2f &p2D);
  66. cv::Mat projectJac(const cv::Point3f &p3D);
  67. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  68. cv::Mat unprojectJac(const cv::Point2f &p2D);
  69. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  70. cv::Mat &R21, cv::Mat &t21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  71. cv::Mat toK();
  72. 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);
  73. 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);
  74. std::vector<int> mvLappingArea;
  75. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  76. cv::Mat& Tcw1, cv::Mat& Tcw2,
  77. const float sigmaLevel1, const float sigmaLevel2,
  78. cv::Mat& x3Dtriangulated);
  79. friend std::ostream& operator<<(std::ostream& os, const KannalaBrandt8& kb);
  80. friend std::istream& operator>>(std::istream& is, KannalaBrandt8& kb);
  81. private:
  82. const float precision;
  83. //Parameters vector corresponds to
  84. //[fx, fy, cx, cy, k0, k1, k2, k3]
  85. TwoViewReconstruction* tvr;
  86. void Triangulate(const cv::Point2f &p1, const cv::Point2f &p2, const cv::Mat &Tcw1, const cv::Mat &Tcw2,cv::Mat &x3D);
  87. };
  88. }
  89. //BOOST_CLASS_EXPORT_KEY(ORBSLAM2::KannalaBrandt8)
  90. #endif //CAMERAMODELS_KANNALABRANDT8_H