Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"C_Cpp.default.configurationProvider": "ms-vscode.cmake-tools"
}
2 changes: 2 additions & 0 deletions Examples/Monocular/KITTI00-02.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 718.856
Camera.fy: 718.856
Expand Down
2 changes: 2 additions & 0 deletions Examples/Monocular/KITTI03.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 721.5377
Camera.fy: 721.5377
Expand Down
2 changes: 2 additions & 0 deletions Examples/Monocular/KITTI04-12.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 707.0912
Camera.fy: 707.0912
Expand Down
2 changes: 2 additions & 0 deletions Examples/Monocular/TUM1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306408
Camera.fy: 516.469215
Expand Down
2 changes: 2 additions & 0 deletions Examples/Monocular/TUM2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 520.908620
Camera.fy: 521.007327
Expand Down
2 changes: 2 additions & 0 deletions Examples/Monocular/TUM3.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 535.4
Camera.fy: 539.2
Expand Down
3 changes: 3 additions & 0 deletions Examples/RGB-D/TUM1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"


# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 517.306408
Camera.fy: 516.469215
Expand Down
3 changes: 3 additions & 0 deletions Examples/RGB-D/TUM2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"


# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 520.908620
Camera.fy: 521.007327
Expand Down
3 changes: 3 additions & 0 deletions Examples/RGB-D/TUM3.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"


# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 535.4
Camera.fy: 539.2
Expand Down
51 changes: 51 additions & 0 deletions Examples/Stereo/KITTI00-02.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 718.856
Camera.fy: 718.856
Expand Down Expand Up @@ -32,6 +34,55 @@ Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35

# Opencv format

LEFT.height: 1241
LEFT.width: 376
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [718.856, 0.0, 607.1928, 0.0, 718.856, 185.2157, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.188560000000e+02, 0.000000000000e+00, 6.071928000000e+02, 0.000000000000e+00, 0.000000000000e+00, 7.188560000000e+02, 1.852157000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]

RIGHT.height: 1241
RIGHT.width: 376
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [718.856, 0.0, 607.1928, 0.0, 718.856, 185.2157, 0.0, 0.0, 1.0]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.188560000000e+02, 0.000000000000e+00, 6.071928000000e+02, -3.861448000000e+02, 0.000000000000e+00, 7.188560000000e+02, 1.852157000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]


#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
Expand Down
52 changes: 52 additions & 0 deletions Examples/Stereo/KITTI03.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 721.5377
Camera.fy: 721.5377
Expand Down Expand Up @@ -32,6 +34,56 @@ Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40


# Opencv format

LEFT.height: 1241
LEFT.width: 376
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [721.5377, 0.0, 609.5593, 0.0, 721.5377, 172.854, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.215377000000e+02, 0.000000000000e+00, 6.095593000000e+02, 0.000000000000e+00, 0.000000000000e+00, 7.215377000000e+02, 1.728540000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]

RIGHT.height: 1241
RIGHT.width: 376
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [721.5377, 0.0, 609.5593, 0.0, 721.5377, 172.854, 0.0, 0.0, 1.0]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.215377000000e+02, 0.000000000000e+00, 6.095593000000e+02, -3.875744000000e+02, 0.000000000000e+00, 7.215377000000e+02, 1.728540000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]


#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
Expand Down
52 changes: 52 additions & 0 deletions Examples/Stereo/KITTI04-12.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------

Camera.type: "PinHole"

# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 707.0912
Camera.fy: 707.0912
Expand Down Expand Up @@ -32,6 +34,56 @@ Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 40


# Opencv format

LEFT.height: 1241
LEFT.width: 376
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [707.0912, 0.0, 601.8873, 0.0, 707.0912, 183.1104, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.070912000000e+02, 0.000000000000e+00, 6.018873000000e+02, 0.000000000000e+00, 0.000000000000e+00, 7.070912000000e+02, 1.831104000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]

RIGHT.height: 1241
RIGHT.width: 376
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [707.0912, 0.0, 601.8873, 0.0, 707.0912, 183.1104, 0.0, 0.0, 1.0]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.070912000000e+02, 0.000000000000e+00, 6.018873000000e+02, -3.798145000000e+02, 0.000000000000e+00, 7.070912000000e+02, 1.831104000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]


#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
Expand Down
2 changes: 1 addition & 1 deletion include/Frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<Frame*>(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<Frame*>(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<Frame*>(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<Frame*>(NULL), const IMU::Calib &ImuCalib = IMU::Calib());
Expand Down
2 changes: 1 addition & 1 deletion include/LoopClosing.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class LoopClosing

typedef pair<set<KeyFrame*>,int> ConsistentGroup;
typedef map<KeyFrame*,g2o::Sim3,std::less<KeyFrame*>,
Eigen::aligned_allocator<std::pair<const KeyFrame*, g2o::Sim3> > > KeyFrameAndPose;
Eigen::aligned_allocator<std::pair<KeyFrame *const, g2o::Sim3> > > KeyFrameAndPose;

public:

Expand Down
12 changes: 6 additions & 6 deletions src/Frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<ORBextractor*>(NULL)),
mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth),
mImuCalib(ImuCalib), mpImuPreintegrated(NULL), mpPrevFrame(pPrevF), mpImuPreintegratedFrame(NULL), mpReferenceKF(static_cast<KeyFrame*>(NULL)), mbImuPreintegrated(false),
mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0)
mpCamera(pCamera), mpCamera2(nullptr), mTimeStereoMatch(0), mTimeORB_Ext(0)
{
// Frame ID
mnId=nNextId++;
Expand Down Expand Up @@ -255,10 +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
Nleft = -1;
Nright = -1;
Expand All @@ -269,6 +265,10 @@ Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeSt
mvStereo3Dpoints = vector<cv::Mat>(0);
monoLeft = -1;
monoRight = -1;

AssignFeaturesToGrid();

mpMutexImu = new std::mutex();
}


Expand Down
2 changes: 1 addition & 1 deletion src/Tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down