Pinhole.h 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  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. 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. cv::Point2f project(const cv::Matx31f &m3D);
  52. cv::Point2f project(const cv::Mat &m3D);
  53. Eigen::Vector2d project(const Eigen::Vector3d & v3D);
  54. cv::Mat projectMat(const cv::Point3f& p3D);
  55. float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
  56. cv::Point3f unproject(const cv::Point2f &p2D);
  57. cv::Mat unprojectMat(const cv::Point2f &p2D);
  58. cv::Matx31f unprojectMat_(const cv::Point2f &p2D);
  59. cv::Mat projectJac(const cv::Point3f &p3D);
  60. Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
  61. cv::Mat unprojectJac(const cv::Point2f &p2D);
  62. bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
  63. cv::Mat &R21, cv::Mat &t21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated);
  64. cv::Mat toK();
  65. cv::Matx33f toK_();
  66. 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);
  67. bool epipolarConstrain_(GeometricCamera* pCamera2, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Matx33f& R12, const cv::Matx31f& t12, const float sigmaLevel, const float unc);
  68. bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
  69. cv::Mat& Tcw1, cv::Mat& Tcw2,
  70. const float sigmaLevel1, const float sigmaLevel2,
  71. cv::Mat& x3Dtriangulated) { return false;}
  72. friend std::ostream& operator<<(std::ostream& os, const Pinhole& ph);
  73. friend std::istream& operator>>(std::istream& os, Pinhole& ph);
  74. private:
  75. cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
  76. cv::Matx33f SkewSymmetricMatrix_(const cv::Matx31f &v);
  77. //Parameters vector corresponds to
  78. // [fx, fy, cx, cy]
  79. TwoViewReconstruction* tvr;
  80. };
  81. }
  82. //BOOST_CLASS_EXPORT_KEY(ORBSLAM2::Pinhole)
  83. #endif //CAMERAMODELS_PINHOLE_H