123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110 |
- #ifndef CAMERAMODELS_PINHOLE_H
- #define CAMERAMODELS_PINHOLE_H
- #include <assert.h>
- #include <vector>
- #include <opencv2/core/core.hpp>
- #include <boost/serialization/serialization.hpp>
- #include <boost/serialization/base_object.hpp>
- #include <boost/serialization/vector.hpp>
- #include <boost/serialization/assume_abstract.hpp>
- #include "GeometricCamera.h"
- #include "TwoViewReconstruction.h"
- namespace ORB_SLAM3 {
- class Pinhole : public GeometricCamera {
- friend class boost::serialization::access;
- template<class Archive>
- void serialize(Archive& ar, const unsigned int version)
- {
- ar & boost::serialization::base_object<GeometricCamera>(*this);
- }
- public:
- Pinhole() {
- mvParameters.resize(4);
- mnId=nNextId++;
- mnType = CAM_PINHOLE;
- }
- Pinhole(const std::vector<float> _vParameters) : GeometricCamera(_vParameters), tvr(nullptr) {
- assert(mvParameters.size() == 4);
- mnId=nNextId++;
- mnType = CAM_PINHOLE;
- }
- Pinhole(Pinhole* pPinhole) : GeometricCamera(pPinhole->mvParameters), tvr(nullptr) {
- assert(mvParameters.size() == 4);
- mnId=nNextId++;
- mnType = CAM_PINHOLE;
- }
- ~Pinhole(){
- if(tvr) delete tvr;
- }
- cv::Point2f project(const cv::Point3f &p3D);
- cv::Point2f project(const cv::Mat &m3D);
- Eigen::Vector2d project(const Eigen::Vector3d & v3D);
- cv::Mat projectMat(const cv::Point3f& p3D);
- float uncertainty2(const Eigen::Matrix<double,2,1> &p2D);
- cv::Point3f unproject(const cv::Point2f &p2D);
- cv::Mat unprojectMat(const cv::Point2f &p2D);
- cv::Mat projectJac(const cv::Point3f &p3D);
- Eigen::Matrix<double,2,3> projectJac(const Eigen::Vector3d& v3D);
- cv::Mat unprojectJac(const cv::Point2f &p2D);
- 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);
- cv::Mat toK();
- 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);
- 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) { return false;}
- friend std::ostream& operator<<(std::ostream& os, const Pinhole& ph);
- friend std::istream& operator>>(std::istream& os, Pinhole& ph);
- private:
- cv::Mat SkewSymmetricMatrix(const cv::Mat &v);
-
-
- TwoViewReconstruction* tvr;
- };
- }
- #endif
|