diff --git a/Examples/RGB-D/TUM1.yaml b/Examples/RGB-D/TUM1.yaml index d049a68fcc..717bc36de0 100644 --- a/Examples/RGB-D/TUM1.yaml +++ b/Examples/RGB-D/TUM1.yaml @@ -3,6 +3,7 @@ #-------------------------------------------------------------------------------------------- # Camera Parameters. Adjust them! #-------------------------------------------------------------------------------------------- +Camera.type: "PinHole" # Camera calibration and distortion parameters (OpenCV) Camera.fx: 517.306408 diff --git a/Examples/RGB-D/TUM2.yaml b/Examples/RGB-D/TUM2.yaml index 4c309ee98d..13c326b213 100644 --- a/Examples/RGB-D/TUM2.yaml +++ b/Examples/RGB-D/TUM2.yaml @@ -3,6 +3,7 @@ #-------------------------------------------------------------------------------------------- # Camera Parameters. Adjust them! #-------------------------------------------------------------------------------------------- +Camera.type: "PinHole" # Camera calibration and distortion parameters (OpenCV) Camera.fx: 520.908620 diff --git a/Examples/RGB-D/TUM3.yaml b/Examples/RGB-D/TUM3.yaml index 5a5ff409e4..49235ddbcc 100644 --- a/Examples/RGB-D/TUM3.yaml +++ b/Examples/RGB-D/TUM3.yaml @@ -3,6 +3,7 @@ #-------------------------------------------------------------------------------------------- # Camera Parameters. Adjust them! #-------------------------------------------------------------------------------------------- +Camera.type: "PinHole" # Camera calibration and distortion parameters (OpenCV) Camera.fx: 535.4 diff --git a/include/Frame.h b/include/Frame.h index 5560cf5127..c896bc23e0 100644 --- a/include/Frame.h +++ b/include/Frame.h @@ -56,7 +56,7 @@ class Frame Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); // Constructor for RGB-D cameras. - Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); + Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); // Constructor for Monocular cameras. Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, GeometricCamera* pCamera, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF = static_cast(NULL), const IMU::Calib &ImuCalib = IMU::Calib()); diff --git a/src/Frame.cc b/src/Frame.cc index b22b8dda05..4ed93939f8 100644 --- a/src/Frame.cc +++ b/src/Frame.cc @@ -189,11 +189,11 @@ Frame::Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeSt monoRight = -1; } -Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, Frame* pPrevF, const IMU::Calib &ImuCalib) +Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, GeometricCamera* pCamera,Frame* pPrevF, const IMU::Calib &ImuCalib) :mpcpi(NULL),mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth), mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast(NULL)), mbImuPreintegrated(false), - mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0) + mpCamera(pCamera),mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0) { // Frame ID mnId=nNextId++; @@ -255,8 +255,6 @@ Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeSt mb = mbf/fx; - AssignFeaturesToGrid(); - mpMutexImu = new std::mutex(); //Set no stereo fisheye information @@ -269,6 +267,8 @@ Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeSt mvStereo3Dpoints = vector(0); monoLeft = -1; monoRight = -1; + + AssignFeaturesToGrid(); } diff --git a/src/Tracking.cc b/src/Tracking.cc index d6f82fca1a..ea88103e48 100644 --- a/src/Tracking.cc +++ b/src/Tracking.cc @@ -441,7 +441,7 @@ cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const d imDepth.convertTo(imDepth,CV_32F,mDepthMapFactor); std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now(); - mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth); + mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth,mpCamera); mCurrentFrame.mNameFile = filename; mCurrentFrame.mnDataset = mnNumDataset;