GeometricCamera.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  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_GEOMETRICCAMERA_H
  19. #define CAMERAMODELS_GEOMETRICCAMERA_H
  20. #include <vector>
  21. #include <opencv2/core/core.hpp>
  22. #include <opencv2/imgproc/imgproc.hpp>
  23. #include <opencv2/features2d/features2d.hpp>
  24. #include <boost/serialization/serialization.hpp>
  25. #include <boost/serialization/access.hpp>
  26. #include <boost/serialization/base_object.hpp>
  27. #include <boost/serialization/export.hpp>
  28. #include <boost/serialization/vector.hpp>
  29. #include <boost/serialization/assume_abstract.hpp>
  30. #include <sophus/se3.hpp>
  31. #include <Eigen/Geometry>
  32. #include "Converter.h"
  33. #include "GeometricTools.h"
  34. namespace ORB_SLAM3 {
  35. class GeometricCamera {
  36. friend class boost::serialization::access;
  37. template<class Archive>
  38. void serialize(Archive& ar, const unsigned int version)
  39. {
  40. ar & mnId;
  41. ar & mnType;
  42. ar & mvParameters;
  43. }
  44. public:
  45. GeometricCamera() {}
  46. GeometricCamera(const std::vector<float> &_vParameters) : mvParameters(_vParameters) {}
  47. ~GeometricCamera() {}
  48. virtual cv::Point2f project(const cv::Point3f &p3D) = 0;
  49. virtual Eigen::Vector2d project(const Eigen::Vector3d & v3D) = 0;
  50. virtual Eigen::Vector2f project(const Eigen::Vector3f & v3D) = 0;
  51. virtual Eigen::Vector2f projectMat(const cv::Point3f& p3D) = 0;
  52. virtual float uncertainty2(const Eigen::Matrix<double,2,1> &p2D) = 0;
  53. virtual Eigen::Vector3f unprojectEig(const cv::Point2f &p2D) = 0;
  54. virtual cv::Point3f unproject(const cv::Point2f &p2D) = 0;
  55. virtual Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D) = 0;
  56. virtual bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  57. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated) = 0;
  58. virtual cv::Mat toK() = 0;
  59. virtual Eigen::Matrix3f toK_() = 0;
  60. virtual bool epipolarConstrain(GeometricCamera* otherCamera, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const Eigen::Matrix3f& R12, const Eigen::Vector3f& t12, const float sigmaLevel, const float unc) = 0;
  61. float getParameter(const int i){return mvParameters[i];}
  62. void setParameter(const float p, const size_t i){mvParameters[i] = p;}
  63. size_t size(){return mvParameters.size();}
  64. virtual bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  65. Sophus::SE3f& Tcw1, Sophus::SE3f& Tcw2,
  66. const float sigmaLevel1, const float sigmaLevel2,
  67. Eigen::Vector3f& x3Dtriangulated) = 0;
  68. unsigned int GetId() { return mnId; }
  69. unsigned int GetType() { return mnType; }
  70. const static unsigned int CAM_PINHOLE = 0;
  71. const static unsigned int CAM_FISHEYE = 1;
  72. static long unsigned int nNextId;
  73. protected:
  74. std::vector<float> mvParameters;
  75. unsigned int mnId;
  76. unsigned int mnType;
  77. };
  78. }
  79. #endif //CAMERAMODELS_GEOMETRICCAMERA_H