123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899 |
- namespace ORB_SLAM3 {
- class GeometricCamera {
- public:
- GeometricCamera() {}
- GeometricCamera(const std::vector<float> &_vParameters) : mvParameters(_vParameters) {}
- ~GeometricCamera() {}
- virtual cv::Point2f project(const cv::Point3f &p3D) = 0;
- virtual cv::Point2f project(const cv::Matx31f &m3D) = 0;
- virtual cv::Point2f project(const cv::Mat& m3D) = 0;
- virtual Eigen::Vector2d project(const Eigen::Vector3d & v3D) = 0;
- virtual cv::Mat projectMat(const cv::Point3f& p3D) = 0;
- virtual float uncertainty2(const Eigen::Matrix<double,2,1> &p2D) = 0;
- virtual cv::Point3f unproject(const cv::Point2f &p2D) = 0;
- virtual cv::Mat unprojectMat(const cv::Point2f &p2D) = 0;
- virtual cv::Matx31f unprojectMat_(const cv::Point2f &p2D) = 0;
- virtual cv::Mat projectJac(const cv::Point3f &p3D) = 0;
- virtual Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D) = 0;
- virtual cv::Mat unprojectJac(const cv::Point2f &p2D) = 0;
- virtual bool ReconstructWithTwoViews(const std::vector<cv::KeyPoint>& vKeys1, const std::vector<cv::KeyPoint>& vKeys2, const std::vector<int> &vMatches12,
- cv::Mat &R21, cv::Mat &t21, std::vector<cv::Point3f> &vP3D, std::vector<bool> &vbTriangulated) = 0;
- virtual cv::Mat toK() = 0;
- virtual cv::Matx33f toK_() = 0;
- virtual bool epipolarConstrain(GeometricCamera* otherCamera, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Mat& R12, const cv::Mat& t12, const float sigmaLevel, const float unc) = 0;
- virtual bool epipolarConstrain_(GeometricCamera* otherCamera, const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, const cv::Matx33f& R12, const cv::Matx31f& t12, const float sigmaLevel, const float unc) = 0;
- float getParameter(const int i){return mvParameters[i];}
- void setParameter(const float p, const size_t i){mvParameters[i] = p;}
- size_t size(){return mvParameters.size();}
- virtual bool matchAndtriangulate(const cv::KeyPoint& kp1, const cv::KeyPoint& kp2, GeometricCamera* pOther,
- cv::Mat& Tcw1, cv::Mat& Tcw2,
- const float sigmaLevel1, const float sigmaLevel2,
- cv::Mat& x3Dtriangulated) = 0;
- unsigned int GetId() { return mnId; }
- unsigned int GetType() { return mnType; }
- const unsigned int CAM_PINHOLE = 0;
- const unsigned int CAM_FISHEYE = 1;
- static long unsigned int nNextId;
- protected:
- std::vector<float> mvParameters;
- unsigned int mnId;
- unsigned int mnType;
- };
- }
|