Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Jf99 fix camera2DistortionCoef() #787

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
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
64 changes: 32 additions & 32 deletions include/Settings.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,8 @@ namespace ORB_SLAM3 {
CameraType cameraType() {return cameraType_;}
GeometricCamera* camera1() {return calibration1_;}
GeometricCamera* camera2() {return calibration2_;}
cv::Mat camera1DistortionCoef() {return cv::Mat(vPinHoleDistorsion1_.size(),1,CV_32F,vPinHoleDistorsion1_.data());}
cv::Mat camera2DistortionCoef() {return cv::Mat(vPinHoleDistorsion2_.size(),1,CV_32F,vPinHoleDistorsion1_.data());}
cv::Mat camera1DistortionCoef() {return cv::Mat(vPinHoleDistortion1_.size(),1,CV_32F,vPinHoleDistortion1_.data());}
cv::Mat camera2DistortionCoef() {return cv::Mat(vPinHoleDistortion2_.size(),1,CV_32F,vPinHoleDistortion2_.data());}

Sophus::SE3f Tlr() {return Tlr_;}
float bf() {return bf_;}
Expand Down Expand Up @@ -156,27 +156,27 @@ namespace ORB_SLAM3 {

void precomputeRectificationMaps();

int sensor_;
CameraType cameraType_; //Camera type
int sensor_ = 0;
CameraType cameraType_ = PinHole;

/*
* Visual stuff
*/
GeometricCamera* calibration1_, *calibration2_; //Camera calibration
GeometricCamera* originalCalib1_, *originalCalib2_;
std::vector<float> vPinHoleDistorsion1_, vPinHoleDistorsion2_;
GeometricCamera* calibration1_ = nullptr, *calibration2_ = nullptr; //Camera calibration
GeometricCamera* originalCalib1_ = nullptr, *originalCalib2_ = nullptr;
std::vector<float> vPinHoleDistortion1_, vPinHoleDistortion2_;

cv::Size originalImSize_, newImSize_;
float fps_;
bool bRGB_;
float fps_ = 1.f;
bool bRGB_ = false;

bool bNeedToUndistort_;
bool bNeedToRectify_;
bool bNeedToResize1_, bNeedToResize2_;
bool bNeedToUndistort_ = false;
bool bNeedToRectify_ = false;
bool bNeedToResize1_ = false, bNeedToResize2_ = false;

Sophus::SE3f Tlr_;
float thDepth_;
float bf_, b_;
float thDepth_ = 60.f;
float bf_ = 0.f, b_ = 0.f;

/*
* Rectification stuff
Expand All @@ -187,36 +187,36 @@ namespace ORB_SLAM3 {
/*
* Inertial stuff
*/
float noiseGyro_, noiseAcc_;
float gyroWalk_, accWalk_;
float imuFrequency_;
float noiseGyro_ = 0.f, noiseAcc_ = 0.f;
float gyroWalk_ = 0.f, accWalk_ = 0.f;
float imuFrequency_ = 0.f;
Sophus::SE3f Tbc_;
bool insertKFsWhenLost_;
bool insertKFsWhenLost_ = false;

/*
* RGBD stuff
*/
float depthMapFactor_;
float depthMapFactor_ = 1.f;

/*
* ORB stuff
*/
int nFeatures_;
float scaleFactor_;
int nLevels_;
int initThFAST_, minThFAST_;
int nFeatures_ = 1000;
float scaleFactor_ = 1.f;
int nLevels_ = 1;
int initThFAST_ = 20, minThFAST_ = 7;

/*
* Viewer stuff
*/
float keyFrameSize_;
float keyFrameLineWidth_;
float graphLineWidth_;
float pointSize_;
float cameraSize_;
float cameraLineWidth_;
float viewPointX_, viewPointY_, viewPointZ_, viewPointF_;
float imageViewerScale_;
float keyFrameSize_ = 0.05f;
float keyFrameLineWidth_ = 1.f;
float graphLineWidth_ = 0.9f;
float pointSize_ = 2.f;
float cameraSize_ = 0.08f;
float cameraLineWidth_ = 3.f;
float viewPointX_ = 0.f, viewPointY_ = 0.f, viewPointZ_ = 0.f, viewPointF_ = 100.f;
float imageViewerScale_ = 1.f;

/*
* Save & load maps
Expand All @@ -226,7 +226,7 @@ namespace ORB_SLAM3 {
/*
* Other stuff
*/
float thFarPoints_;
float thFarPoints_ = 100.f;

};
};
Expand Down
38 changes: 19 additions & 19 deletions src/Settings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -207,20 +207,20 @@ namespace ORB_SLAM3 {
if(found){
readParameter<float>(fSettings,"Camera1.k3",found,false);
if(found){
vPinHoleDistorsion1_.resize(5);
vPinHoleDistorsion1_[4] = readParameter<float>(fSettings,"Camera1.k3",found);
vPinHoleDistortion1_.resize(5);
vPinHoleDistortion1_[4] = readParameter<float>(fSettings,"Camera1.k3",found);
}
else{
vPinHoleDistorsion1_.resize(4);
vPinHoleDistortion1_.resize(4);
}
vPinHoleDistorsion1_[0] = readParameter<float>(fSettings,"Camera1.k1",found);
vPinHoleDistorsion1_[1] = readParameter<float>(fSettings,"Camera1.k2",found);
vPinHoleDistorsion1_[2] = readParameter<float>(fSettings,"Camera1.p1",found);
vPinHoleDistorsion1_[3] = readParameter<float>(fSettings,"Camera1.p2",found);
vPinHoleDistortion1_[0] = readParameter<float>(fSettings,"Camera1.k1",found);
vPinHoleDistortion1_[1] = readParameter<float>(fSettings,"Camera1.k2",found);
vPinHoleDistortion1_[2] = readParameter<float>(fSettings,"Camera1.p1",found);
vPinHoleDistortion1_[3] = readParameter<float>(fSettings,"Camera1.p2",found);
}

//Check if we need to correct distortion from the images
if((sensor_ == System::MONOCULAR || sensor_ == System::IMU_MONOCULAR) && vPinHoleDistorsion1_.size() != 0){
if((sensor_ == System::MONOCULAR || sensor_ == System::IMU_MONOCULAR) && vPinHoleDistortion1_.size() != 0){
bNeedToUndistort_ = true;
}
}
Expand Down Expand Up @@ -296,16 +296,16 @@ namespace ORB_SLAM3 {
if(found){
readParameter<float>(fSettings,"Camera2.k3",found,false);
if(found){
vPinHoleDistorsion2_.resize(5);
vPinHoleDistorsion2_[4] = readParameter<float>(fSettings,"Camera2.k3",found);
vPinHoleDistortion2_.resize(5);
vPinHoleDistortion2_[4] = readParameter<float>(fSettings,"Camera2.k3",found);
}
else{
vPinHoleDistorsion2_.resize(4);
vPinHoleDistortion2_.resize(4);
}
vPinHoleDistorsion2_[0] = readParameter<float>(fSettings,"Camera2.k1",found);
vPinHoleDistorsion2_[1] = readParameter<float>(fSettings,"Camera2.k2",found);
vPinHoleDistorsion2_[2] = readParameter<float>(fSettings,"Camera2.p1",found);
vPinHoleDistorsion2_[3] = readParameter<float>(fSettings,"Camera2.p2",found);
vPinHoleDistortion2_[0] = readParameter<float>(fSettings,"Camera2.k1",found);
vPinHoleDistortion2_[1] = readParameter<float>(fSettings,"Camera2.k2",found);
vPinHoleDistortion2_[2] = readParameter<float>(fSettings,"Camera2.p1",found);
vPinHoleDistortion2_[3] = readParameter<float>(fSettings,"Camera2.p2",found);
}
}
else if(cameraType_ == KannalaBrandt){
Expand Down Expand Up @@ -542,9 +542,9 @@ namespace ORB_SLAM3 {
}
output << " ]" << endl;

if(!settings.vPinHoleDistorsion1_.empty()){
if(!settings.vPinHoleDistortion1_.empty()){
output << "\t-Camera 1 distortion parameters: [ ";
for(float d : settings.vPinHoleDistorsion1_){
for(float d : settings.vPinHoleDistortion1_){
output << " " << d;
}
output << " ]" << endl;
Expand All @@ -564,9 +564,9 @@ namespace ORB_SLAM3 {
}
output << " ]" << endl;

if(!settings.vPinHoleDistorsion2_.empty()){
if(!settings.vPinHoleDistortion2_.empty()){
output << "\t-Camera 1 distortion parameters: [ ";
for(float d : settings.vPinHoleDistorsion2_){
for(float d : settings.vPinHoleDistortion2_){
output << " " << d;
}
output << " ]" << endl;
Expand Down