Pinhole.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  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_PINHOLE_H
  19. #define CAMERAMODELS_PINHOLE_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 <boost/serialization/assume_abstract.hpp>
  27. #include "GeometricCamera.h"
  28. #include "TwoViewReconstruction.h"
  29. namespace ORB_SLAM3 {
  30. class Pinhole : public GeometricCamera {
  31. friend class boost::serialization::access;
  32. template<class Archive>
  33. void serialize(Archive& ar, const unsigned int version)
  34. {
  35. ar & boost::serialization::base_object<GeometricCamera>(*this);
  36. }
  37. public:
  38. Pinhole() {
  39. mvParameters.resize(4);
  40. mnId=nNextId++;
  41. mnType = CAM_PINHOLE;
  42. }
  43. Pinhole(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), tvr(nullptr) {
  44. assert(mvParameters.size() == 4);
  45. mnId=nNextId++;
  46. mnType = CAM_PINHOLE;
  47. }
  48. Pinhole(Pinhole* pPinhole) : GeometricCamera(pPinhole->mvParameters), tvr(nullptr) {
  49. assert(mvParameters.size() == 4);
  50. mnId=nNextId++;
  51. mnType = CAM_PINHOLE;
  52. }
  53. ~Pinhole(){
  54. if(tvr) delete tvr;
  55. }
  56. cv::Point2f project(const cv::Point3f &p3D);
  57. cv::Point2f project(const cv::Mat &m3D);
  58. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  59. cv::Mat projectMat(const cv::Point3f& p3D);
  60. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  61. cv::Point3f unproject(const cv::Point2f &p2D);
  62. cv::Mat unprojectMat(const cv::Point2f &p2D);
  63. cv::Mat projectJac(const cv::Point3f &p3D);
  64. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  65. cv::Mat unprojectJac(const cv::Point2f &p2D);
  66. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  67. cv::Mat &R21, cv::Mat &t21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  68. cv::Mat toK();
  69. 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);
  70. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  71. cv::Mat& Tcw1, cv::Mat& Tcw2,
  72. const float sigmaLevel1, const float sigmaLevel2,
  73. cv::Mat& x3Dtriangulated) { return false;}
  74. friend std::ostream& operator<<(std::ostream& os, const Pinhole& ph);
  75. friend std::istream& operator>>(std::istream& os, Pinhole& ph);
  76. private:
  77. cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
  78. //Parameters vector corresponds to
  79. // [fx, fy, cx, cy]
  80. TwoViewReconstruction* tvr;
  81. };
  82. }
  83. //BOOST_CLASS_EXPORT_KEY(ORBSLAM2::Pinhole)
  84. #endif //CAMERAMODELS_PINHOLE_H