Pinhole.h 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101
  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_PINHOLE_H
  19. #define CAMERAMODELS_PINHOLE_H
  20. #include <assert.h>
  21. #include "GeometricCamera.h"
  22. #include "TwoViewReconstruction.h"
  23. namespace ORB_SLAM3 {
  24. class Pinhole : 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. }
  31. public:
  32. Pinhole() {
  33. mvParameters.resize(4);
  34. mnId=nNextId++;
  35. mnType = CAM_PINHOLE;
  36. }
  37. Pinhole(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), tvr(nullptr) {
  38. assert(mvParameters.size() == 4);
  39. mnId=nNextId++;
  40. mnType = CAM_PINHOLE;
  41. }
  42. Pinhole(Pinhole* pPinhole) : GeometricCamera(pPinhole->mvParameters), tvr(nullptr) {
  43. assert(mvParameters.size() == 4);
  44. mnId=nNextId++;
  45. mnType = CAM_PINHOLE;
  46. }
  47. ~Pinhole(){
  48. if(tvr) delete tvr;
  49. }
  50. cv::Point2f project(const cv::Point3f &p3D);
  51. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  52. Eigen::Vector2f project(const Eigen::Vector3f & v3D);
  53. Eigen::Vector2f projectMat(const cv::Point3f& p3D);
  54. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  55. Eigen::Vector3f unprojectEig(const cv::Point2f &p2D);
  56. cv::Point3f unproject(const cv::Point2f &p2D);
  57. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  58. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  59. Sophus::SE3f &T21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  60. cv::Mat toK();
  61. Eigen::Matrix3f toK_();
  62. 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);
  63. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  64. Sophus::SE3f& Tcw1, Sophus::SE3f& Tcw2,
  65. const float sigmaLevel1, const float sigmaLevel2,
  66. Eigen::Vector3f& x3Dtriangulated) { return false;}
  67. friend std::ostream& operator<<(std::ostream& os, const Pinhole& ph);
  68. friend std::istream& operator>>(std::istream& os, Pinhole& ph);
  69. bool IsEqual(GeometricCamera* pCam);
  70. private:
  71. //Parameters vector corresponds to
  72. // [fx, fy, cx, cy]
  73. TwoViewReconstruction* tvr;
  74. };
  75. }
  76. //BOOST_CLASS_EXPORT_KEY(ORBSLAM2::Pinhole)
  77. #endif //CAMERAMODELS_PINHOLE_H