This commit is contained in:
Ivan
2022-06-28 10:36:24 +03:00
commit e4c8529305
160 changed files with 59023 additions and 0 deletions

379
src/util/DatasetReader.h Normal file
View File

@@ -0,0 +1,379 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/settings.h"
#include "util/globalFuncs.h"
#include "util/globalCalib.h"
#include <sstream>
#include <fstream>
#include <dirent.h>
#include <algorithm>
#include "util/Undistort.h"
#include "IOWrapper/ImageRW.h"
#if HAS_ZIPLIB
#include "zip.h"
#endif
#include <boost/thread.hpp>
using namespace dso;
inline int getdir (std::string dir, std::vector<std::string> &files)
{
DIR *dp;
struct dirent *dirp;
if((dp = opendir(dir.c_str())) == NULL)
{
return -1;
}
while ((dirp = readdir(dp)) != NULL) {
std::string name = std::string(dirp->d_name);
if(name != "." && name != "..")
files.push_back(name);
}
closedir(dp);
std::sort(files.begin(), files.end());
if(dir.at( dir.length() - 1 ) != '/') dir = dir+"/";
for(unsigned int i=0;i<files.size();i++)
{
if(files[i].at(0) != '/')
files[i] = dir + files[i];
}
return files.size();
}
struct PrepImageItem
{
int id;
bool isQueud;
ImageAndExposure* pt;
inline PrepImageItem(int _id)
{
id=_id;
isQueud = false;
pt=0;
}
inline void release()
{
if(pt!=0) delete pt;
pt=0;
}
};
class ImageFolderReader
{
public:
ImageFolderReader(std::string path, std::string calibFile, std::string gammaFile, std::string vignetteFile)
{
this->path = path;
this->calibfile = calibFile;
#if HAS_ZIPLIB
ziparchive=0;
databuffer=0;
#endif
isZipped = (path.length()>4 && path.substr(path.length()-4) == ".zip");
if(isZipped)
{
#if HAS_ZIPLIB
int ziperror=0;
ziparchive = zip_open(path.c_str(), ZIP_RDONLY, &ziperror);
if(ziperror!=0)
{
printf("ERROR %d reading archive %s!\n", ziperror, path.c_str());
exit(1);
}
files.clear();
int numEntries = zip_get_num_entries(ziparchive, 0);
for(int k=0;k<numEntries;k++)
{
const char* name = zip_get_name(ziparchive, k, ZIP_FL_ENC_STRICT);
std::string nstr = std::string(name);
if(nstr == "." || nstr == "..") continue;
files.push_back(name);
}
printf("got %d entries and %d files!\n", numEntries, (int)files.size());
std::sort(files.begin(), files.end());
#else
printf("ERROR: cannot read .zip archive, as compile without ziplib!\n");
exit(1);
#endif
}
else
getdir (path, files);
undistort = Undistort::getUndistorterForFile(calibFile, gammaFile, vignetteFile);
widthOrg = undistort->getOriginalSize()[0];
heightOrg = undistort->getOriginalSize()[1];
width=undistort->getSize()[0];
height=undistort->getSize()[1];
// load timestamps if possible.
loadTimestamps();
printf("ImageFolderReader: got %d files in %s!\n", (int)files.size(), path.c_str());
}
~ImageFolderReader()
{
#if HAS_ZIPLIB
if(ziparchive!=0) zip_close(ziparchive);
if(databuffer!=0) delete databuffer;
#endif
delete undistort;
};
Eigen::VectorXf getOriginalCalib()
{
return undistort->getOriginalParameter().cast<float>();
}
Eigen::Vector2i getOriginalDimensions()
{
return undistort->getOriginalSize();
}
void getCalibMono(Eigen::Matrix3f &K, int &w, int &h)
{
K = undistort->getK().cast<float>();
w = undistort->getSize()[0];
h = undistort->getSize()[1];
}
void setGlobalCalibration()
{
int w_out, h_out;
Eigen::Matrix3f K;
getCalibMono(K, w_out, h_out);
setGlobalCalib(w_out, h_out, K);
}
int getNumImages()
{
return files.size();
}
double getTimestamp(int id)
{
if(timestamps.size()==0) return id*0.1f;
if(id >= (int)timestamps.size()) return 0;
if(id < 0) return 0;
return timestamps[id];
}
void prepImage(int id, bool as8U=false)
{
}
MinimalImageB* getImageRaw(int id)
{
return getImageRaw_internal(id,0);
}
ImageAndExposure* getImage(int id, bool forceLoadDirectly=false)
{
return getImage_internal(id, 0);
}
inline float* getPhotometricGamma()
{
if(undistort==0 || undistort->photometricUndist==0) return 0;
return undistort->photometricUndist->getG();
}
// undistorter. [0] always exists, [1-2] only when MT is enabled.
Undistort* undistort;
private:
MinimalImageB* getImageRaw_internal(int id, int unused)
{
if(!isZipped)
{
// CHANGE FOR ZIP FILE
return IOWrap::readImageBW_8U(files[id]);
}
else
{
#if HAS_ZIPLIB
if(databuffer==0) databuffer = new char[widthOrg*heightOrg*6+10000];
zip_file_t* fle = zip_fopen(ziparchive, files[id].c_str(), 0);
long readbytes = zip_fread(fle, databuffer, (long)widthOrg*heightOrg*6+10000);
if(readbytes > (long)widthOrg*heightOrg*6)
{
printf("read %ld/%ld bytes for file %s. increase buffer!!\n", readbytes,(long)widthOrg*heightOrg*6+10000, files[id].c_str());
delete[] databuffer;
databuffer = new char[(long)widthOrg*heightOrg*30];
fle = zip_fopen(ziparchive, files[id].c_str(), 0);
readbytes = zip_fread(fle, databuffer, (long)widthOrg*heightOrg*30+10000);
if(readbytes > (long)widthOrg*heightOrg*30)
{
printf("buffer still to small (read %ld/%ld). abort.\n", readbytes,(long)widthOrg*heightOrg*30+10000);
exit(1);
}
}
return IOWrap::readStreamBW_8U(databuffer, readbytes);
#else
printf("ERROR: cannot read .zip archive, as compile without ziplib!\n");
exit(1);
#endif
}
}
ImageAndExposure* getImage_internal(int id, int unused)
{
MinimalImageB* minimg = getImageRaw_internal(id, 0);
ImageAndExposure* ret2 = undistort->undistort<unsigned char>(
minimg,
(exposures.size() == 0 ? 1.0f : exposures[id]),
(timestamps.size() == 0 ? 0.0 : timestamps[id]));
delete minimg;
return ret2;
}
inline void loadTimestamps()
{
std::ifstream tr;
std::string timesFile = path.substr(0,path.find_last_of('/')) + "/times.txt";
tr.open(timesFile.c_str());
while(!tr.eof() && tr.good())
{
std::string line;
char buf[1000];
tr.getline(buf, 1000);
int id;
double stamp;
float exposure = 0;
if(3 == sscanf(buf, "%d %lf %f", &id, &stamp, &exposure))
{
timestamps.push_back(stamp);
exposures.push_back(exposure);
}
else if(2 == sscanf(buf, "%d %lf", &id, &stamp))
{
timestamps.push_back(stamp);
exposures.push_back(exposure);
}
}
tr.close();
// check if exposures are correct, (possibly skip)
bool exposuresGood = ((int)exposures.size()==(int)getNumImages()) ;
for(int i=0;i<(int)exposures.size();i++)
{
if(exposures[i] == 0)
{
// fix!
float sum=0,num=0;
if(i>0 && exposures[i-1] > 0) {sum += exposures[i-1]; num++;}
if(i+1<(int)exposures.size() && exposures[i+1] > 0) {sum += exposures[i+1]; num++;}
if(num>0)
exposures[i] = sum/num;
}
if(exposures[i] == 0) exposuresGood=false;
}
if((int)getNumImages() != (int)timestamps.size())
{
printf("set timestamps and exposures to zero!\n");
exposures.clear();
timestamps.clear();
}
if((int)getNumImages() != (int)exposures.size() || !exposuresGood)
{
printf("set EXPOSURES to zero!\n");
exposures.clear();
}
printf("got %d images and %d timestamps and %d exposures.!\n", (int)getNumImages(), (int)timestamps.size(), (int)exposures.size());
}
std::vector<ImageAndExposure*> preloadedImages;
std::vector<std::string> files;
std::vector<double> timestamps;
std::vector<float> exposures;
int width, height;
int widthOrg, heightOrg;
std::string path;
std::string calibfile;
bool isZipped;
#if HAS_ZIPLIB
zip_t* ziparchive;
char* databuffer;
#endif
};

74
src/util/FrameShell.h Normal file
View File

@@ -0,0 +1,74 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/NumType.h"
#include "algorithm"
namespace dso
{
class FrameShell
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
int id; // INTERNAL ID, starting at zero.
int incoming_id; // ID passed into DSO
double timestamp; // timestamp passed into DSO.
// set once after tracking
SE3 camToTrackingRef;
FrameShell* trackingRef;
// constantly adapted.
SE3 camToWorld; // Write: TRACKING, while frame is still fresh; MAPPING: only when locked [shellPoseMutex].
AffLight aff_g2l;
bool poseValid;
// statisitcs
int statistics_outlierResOnThis;
int statistics_goodResOnThis;
int marginalizedAt;
double movedByOpt;
inline FrameShell()
{
id=0;
poseValid=true;
camToWorld = SE3();
timestamp=0;
marginalizedAt=-1;
movedByOpt=0;
statistics_outlierResOnThis=statistics_goodResOnThis=0;
trackingRef=0;
camToTrackingRef = SE3();
}
};
}

View File

@@ -0,0 +1,67 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <cstring>
#include <iostream>
namespace dso
{
class ImageAndExposure
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
float* image; // irradiance. between 0 and 256
int w,h; // width and height;
double timestamp;
float exposure_time; // exposure time in ms.
inline ImageAndExposure(int w_, int h_, double timestamp_=0) : w(w_), h(h_), timestamp(timestamp_)
{
image = new float[w*h];
exposure_time=1;
}
inline ~ImageAndExposure()
{
delete[] image;
}
inline void copyMetaTo(ImageAndExposure &other)
{
other.exposure_time = exposure_time;
}
inline ImageAndExposure* getDeepCopy()
{
ImageAndExposure* img = new ImageAndExposure(w,h,timestamp);
img->exposure_time = exposure_time;
memcpy(img->image, image, w*h*sizeof(float));
return img;
}
};
}

View File

@@ -0,0 +1,216 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/settings.h"
#include "boost/thread.hpp"
#include <stdio.h>
#include <iostream>
namespace dso
{
template<typename Running>
class IndexThreadReduce
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
inline IndexThreadReduce()
{
nextIndex = 0;
maxIndex = 0;
stepSize = 1;
callPerIndex = boost::bind(&IndexThreadReduce::callPerIndexDefault, this, _1, _2, _3, _4);
running = true;
for(int i=0;i<NUM_THREADS;i++)
{
isDone[i] = false;
gotOne[i] = true;
workerThreads[i] = boost::thread(&IndexThreadReduce::workerLoop, this, i);
}
}
inline ~IndexThreadReduce()
{
running = false;
exMutex.lock();
todo_signal.notify_all();
exMutex.unlock();
for(int i=0;i<NUM_THREADS;i++)
workerThreads[i].join();
printf("destroyed ThreadReduce\n");
}
inline void reduce(boost::function<void(int,int,Running*,int)> callPerIndex, int first, int end, int stepSize = 0)
{
memset(&stats, 0, sizeof(Running));
// if(!multiThreading)
// {
// callPerIndex(first, end, &stats, 0);
// return;
// }
if(stepSize == 0)
stepSize = ((end-first)+NUM_THREADS-1)/NUM_THREADS;
//printf("reduce called\n");
boost::unique_lock<boost::mutex> lock(exMutex);
// save
this->callPerIndex = callPerIndex;
nextIndex = first;
maxIndex = end;
this->stepSize = stepSize;
// go worker threads!
for(int i=0;i<NUM_THREADS;i++)
{
isDone[i] = false;
gotOne[i] = false;
}
// let them start!
todo_signal.notify_all();
//printf("reduce waiting for threads to finish\n");
// wait for all worker threads to signal they are done.
while(true)
{
// wait for at least one to finish
done_signal.wait(lock);
//printf("thread finished!\n");
// check if actually all are finished.
bool allDone = true;
for(int i=0;i<NUM_THREADS;i++)
allDone = allDone && isDone[i];
// all are finished! exit.
if(allDone)
break;
}
nextIndex = 0;
maxIndex = 0;
this->callPerIndex = boost::bind(&IndexThreadReduce::callPerIndexDefault, this, _1, _2, _3, _4);
//printf("reduce done (all threads finished)\n");
}
Running stats;
private:
boost::thread workerThreads[NUM_THREADS];
bool isDone[NUM_THREADS];
bool gotOne[NUM_THREADS];
boost::mutex exMutex;
boost::condition_variable todo_signal;
boost::condition_variable done_signal;
int nextIndex;
int maxIndex;
int stepSize;
bool running;
boost::function<void(int,int,Running*,int)> callPerIndex;
void callPerIndexDefault(int i, int j,Running* k, int tid)
{
printf("ERROR: should never be called....\n");
assert(false);
}
void workerLoop(int idx)
{
boost::unique_lock<boost::mutex> lock(exMutex);
while(running)
{
// try to get something to do.
int todo = 0;
bool gotSomething = false;
if(nextIndex < maxIndex)
{
// got something!
todo = nextIndex;
nextIndex+=stepSize;
gotSomething = true;
}
// if got something: do it (unlock in the meantime)
if(gotSomething)
{
lock.unlock();
assert(callPerIndex != 0);
Running s; memset(&s, 0, sizeof(Running));
callPerIndex(todo, std::min(todo+stepSize, maxIndex), &s, idx);
gotOne[idx] = true;
lock.lock();
stats += s;
}
// otherwise wait on signal, releasing lock in the meantime.
else
{
if(!gotOne[idx])
{
lock.unlock();
assert(callPerIndex != 0);
Running s; memset(&s, 0, sizeof(Running));
callPerIndex(0, 0, &s, idx);
gotOne[idx] = true;
lock.lock();
stats += s;
}
isDone[idx] = true;
//printf("worker %d waiting..\n", idx);
done_signal.notify_all();
todo_signal.wait(lock);
}
}
}
};
}

167
src/util/MinimalImage.h Normal file
View File

@@ -0,0 +1,167 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/NumType.h"
#include "algorithm"
namespace dso
{
template<typename T>
class MinimalImage
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
int w;
int h;
T* data;
/*
* creates minimal image with own memory
*/
inline MinimalImage(int w_, int h_) : w(w_), h(h_)
{
data = new T[w*h];
ownData=true;
}
/*
* creates minimal image wrapping around existing memory
*/
inline MinimalImage(int w_, int h_, T* data_) : w(w_), h(h_)
{
data = data_;
ownData=false;
}
inline ~MinimalImage()
{
if(ownData) delete [] data;
}
inline MinimalImage* getClone()
{
MinimalImage* clone = new MinimalImage(w,h);
memcpy(clone->data, data, sizeof(T)*w*h);
return clone;
}
inline T& at(int x, int y) {return data[(int)x+((int)y)*w];}
inline T& at(int i) {return data[i];}
inline void setBlack()
{
memset(data, 0, sizeof(T)*w*h);
}
inline void setConst(T val)
{
for(int i=0;i<w*h;i++) data[i] = val;
}
inline void setPixel1(const float &u, const float &v, T val)
{
at(u+0.5f,v+0.5f) = val;
}
inline void setPixel4(const float &u, const float &v, T val)
{
at(u+1.0f,v+1.0f) = val;
at(u+1.0f,v) = val;
at(u,v+1.0f) = val;
at(u,v) = val;
}
inline void setPixel9(const int &u, const int &v, T val)
{
at(u+1,v-1) = val;
at(u+1,v) = val;
at(u+1,v+1) = val;
at(u,v-1) = val;
at(u,v) = val;
at(u,v+1) = val;
at(u-1,v-1) = val;
at(u-1,v) = val;
at(u-1,v+1) = val;
}
inline void setPixelCirc(const int &u, const int &v, T val)
{
for(int i=-3;i<=3;i++)
{
at(u+3,v+i) = val;
at(u-3,v+i) = val;
at(u+2,v+i) = val;
at(u-2,v+i) = val;
at(u+i,v-3) = val;
at(u+i,v+3) = val;
at(u+i,v-2) = val;
at(u+i,v+2) = val;
}
}
private:
bool ownData;
};
typedef Eigen::Matrix<unsigned char,3,1> Vec3b;
typedef MinimalImage<float> MinimalImageF;
typedef MinimalImage<Vec3f> MinimalImageF3;
typedef MinimalImage<unsigned char> MinimalImageB;
typedef MinimalImage<Vec3b> MinimalImageB3;
typedef MinimalImage<unsigned short> MinimalImageB16;
}

195
src/util/NumType.h Normal file
View File

@@ -0,0 +1,195 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "Eigen/Core"
#include "sophus/sim3.hpp"
#include "sophus/se3.hpp"
namespace dso
{
// CAMERA MODEL TO USE
#define SSEE(val,idx) (*(((float*)&val)+idx))
#define MAX_RES_PER_POINT 8
#define NUM_THREADS 6
#define todouble(x) (x).cast<double>()
typedef Sophus::SE3d SE3;
typedef Sophus::Sim3d Sim3;
typedef Sophus::SO3d SO3;
#define CPARS 4
typedef Eigen::Matrix<double,Eigen::Dynamic,Eigen::Dynamic> MatXX;
typedef Eigen::Matrix<double,CPARS,CPARS> MatCC;
#define MatToDynamic(x) MatXX(x)
typedef Eigen::Matrix<double,CPARS,10> MatC10;
typedef Eigen::Matrix<double,10,10> Mat1010;
typedef Eigen::Matrix<double,13,13> Mat1313;
typedef Eigen::Matrix<double,8,10> Mat810;
typedef Eigen::Matrix<double,8,3> Mat83;
typedef Eigen::Matrix<double,6,6> Mat66;
typedef Eigen::Matrix<double,5,3> Mat53;
typedef Eigen::Matrix<double,4,3> Mat43;
typedef Eigen::Matrix<double,4,2> Mat42;
typedef Eigen::Matrix<double,3,3> Mat33;
typedef Eigen::Matrix<double,2,2> Mat22;
typedef Eigen::Matrix<double,8,CPARS> Mat8C;
typedef Eigen::Matrix<double,CPARS,8> MatC8;
typedef Eigen::Matrix<float,8,CPARS> Mat8Cf;
typedef Eigen::Matrix<float,CPARS,8> MatC8f;
typedef Eigen::Matrix<double,8,8> Mat88;
typedef Eigen::Matrix<double,7,7> Mat77;
typedef Eigen::Matrix<double,CPARS,1> VecC;
typedef Eigen::Matrix<float,CPARS,1> VecCf;
typedef Eigen::Matrix<double,13,1> Vec13;
typedef Eigen::Matrix<double,10,1> Vec10;
typedef Eigen::Matrix<double,9,1> Vec9;
typedef Eigen::Matrix<double,8,1> Vec8;
typedef Eigen::Matrix<double,7,1> Vec7;
typedef Eigen::Matrix<double,6,1> Vec6;
typedef Eigen::Matrix<double,5,1> Vec5;
typedef Eigen::Matrix<double,4,1> Vec4;
typedef Eigen::Matrix<double,3,1> Vec3;
typedef Eigen::Matrix<double,2,1> Vec2;
typedef Eigen::Matrix<double,Eigen::Dynamic,1> VecX;
typedef Eigen::Matrix<float,3,3> Mat33f;
typedef Eigen::Matrix<float,10,3> Mat103f;
typedef Eigen::Matrix<float,2,2> Mat22f;
typedef Eigen::Matrix<float,3,1> Vec3f;
typedef Eigen::Matrix<float,2,1> Vec2f;
typedef Eigen::Matrix<float,6,1> Vec6f;
typedef Eigen::Matrix<double,4,9> Mat49;
typedef Eigen::Matrix<double,8,9> Mat89;
typedef Eigen::Matrix<double,9,4> Mat94;
typedef Eigen::Matrix<double,9,8> Mat98;
typedef Eigen::Matrix<double,8,1> Mat81;
typedef Eigen::Matrix<double,1,8> Mat18;
typedef Eigen::Matrix<double,9,1> Mat91;
typedef Eigen::Matrix<double,1,9> Mat19;
typedef Eigen::Matrix<double,8,4> Mat84;
typedef Eigen::Matrix<double,4,8> Mat48;
typedef Eigen::Matrix<double,4,4> Mat44;
typedef Eigen::Matrix<float,MAX_RES_PER_POINT,1> VecNRf;
typedef Eigen::Matrix<float,12,1> Vec12f;
typedef Eigen::Matrix<float,1,8> Mat18f;
typedef Eigen::Matrix<float,6,6> Mat66f;
typedef Eigen::Matrix<float,8,8> Mat88f;
typedef Eigen::Matrix<float,8,4> Mat84f;
typedef Eigen::Matrix<float,8,1> Vec8f;
typedef Eigen::Matrix<float,10,1> Vec10f;
typedef Eigen::Matrix<float,6,6> Mat66f;
typedef Eigen::Matrix<float,4,1> Vec4f;
typedef Eigen::Matrix<float,4,4> Mat44f;
typedef Eigen::Matrix<float,12,12> Mat1212f;
typedef Eigen::Matrix<float,12,1> Vec12f;
typedef Eigen::Matrix<float,13,13> Mat1313f;
typedef Eigen::Matrix<float,10,10> Mat1010f;
typedef Eigen::Matrix<float,13,1> Vec13f;
typedef Eigen::Matrix<float,9,9> Mat99f;
typedef Eigen::Matrix<float,9,1> Vec9f;
typedef Eigen::Matrix<float,4,2> Mat42f;
typedef Eigen::Matrix<float,6,2> Mat62f;
typedef Eigen::Matrix<float,1,2> Mat12f;
typedef Eigen::Matrix<float,Eigen::Dynamic,1> VecXf;
typedef Eigen::Matrix<float,Eigen::Dynamic,Eigen::Dynamic> MatXXf;
typedef Eigen::Matrix<double,8+CPARS+1,8+CPARS+1> MatPCPC;
typedef Eigen::Matrix<float,8+CPARS+1,8+CPARS+1> MatPCPCf;
typedef Eigen::Matrix<double,8+CPARS+1,1> VecPC;
typedef Eigen::Matrix<float,8+CPARS+1,1> VecPCf;
typedef Eigen::Matrix<float,14,14> Mat1414f;
typedef Eigen::Matrix<float,14,1> Vec14f;
typedef Eigen::Matrix<double,14,14> Mat1414;
typedef Eigen::Matrix<double,14,1> Vec14;
// transforms points from one frame to another.
struct AffLight
{
AffLight(double a_, double b_) : a(a_), b(b_) {};
AffLight() : a(0), b(0) {};
// Affine Parameters:
double a,b; // I_frame = exp(a)*I_global + b. // I_global = exp(-a)*(I_frame - b).
static Vec2 fromToVecExposure(float exposureF, float exposureT, AffLight g2F, AffLight g2T)
{
if(exposureF==0 || exposureT==0)
{
exposureT = exposureF = 1;
//printf("got exposure value of 0! please choose the correct model.\n");
//assert(setting_brightnessTransferFunc < 2);
}
double a = exp(g2T.a-g2F.a) * exposureT / exposureF;
double b = g2T.b - a*g2F.b;
return Vec2(a,b);
}
Vec2 vec()
{
return Vec2(a,b);
}
};
}

1236
src/util/Undistort.cpp Normal file

File diff suppressed because it is too large Load Diff

163
src/util/Undistort.h Normal file
View File

@@ -0,0 +1,163 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/ImageAndExposure.h"
#include "util/MinimalImage.h"
#include "util/NumType.h"
#include "Eigen/Core"
namespace dso
{
class PhotometricUndistorter
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
PhotometricUndistorter(std::string file, std::string noiseImage, std::string vignetteImage, int w_, int h_);
~PhotometricUndistorter();
// removes readout noise, and converts to irradiance.
// affine normalizes values to 0 <= I < 256.
// raw irradiance = a*I + b.
// output will be written in [output].
template<typename T> void processFrame(T* image_in, float exposure_time, float factor=1);
void unMapFloatImage(float* image);
ImageAndExposure* output;
float* getG() {if(!valid) return 0; else return G;};
private:
float G[256*256];
int GDepth;
float* vignetteMap;
float* vignetteMapInv;
int w,h;
bool valid;
};
class Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
virtual ~Undistort();
virtual void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const = 0;
inline const Mat33 getK() const {return K;};
inline const Eigen::Vector2i getSize() const {return Eigen::Vector2i(w,h);};
inline const VecX getOriginalParameter() const {return parsOrg;};
inline const Eigen::Vector2i getOriginalSize() {return Eigen::Vector2i(wOrg,hOrg);};
inline bool isValid() {return valid;};
template<typename T>
ImageAndExposure* undistort(const MinimalImage<T>* image_raw, float exposure=0, double timestamp=0, float factor=1) const;
static Undistort* getUndistorterForFile(std::string configFilename, std::string gammaFilename, std::string vignetteFilename);
void loadPhotometricCalibration(std::string file, std::string noiseImage, std::string vignetteImage);
PhotometricUndistorter* photometricUndist;
protected:
int w, h, wOrg, hOrg, wUp, hUp;
int upsampleUndistFactor;
Mat33 K;
VecX parsOrg;
bool valid;
bool passthrough;
float* remapX;
float* remapY;
void applyBlurNoise(float* img) const;
void makeOptimalK_crop();
void makeOptimalK_full();
void readFromFile(const char* configFileName, int nPars, std::string prefix = "");
};
class UndistortFOV : public Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
UndistortFOV(const char* configFileName, bool noprefix);
~UndistortFOV();
void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const;
};
class UndistortRadTan : public Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
UndistortRadTan(const char* configFileName, bool noprefix);
~UndistortRadTan();
void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const;
};
class UndistortEquidistant : public Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
UndistortEquidistant(const char* configFileName, bool noprefix);
~UndistortEquidistant();
void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const;
};
class UndistortPinhole : public Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
UndistortPinhole(const char* configFileName, bool noprefix);
~UndistortPinhole();
void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const;
private:
float inputCalibration[8];
};
class UndistortKB : public Undistort
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
UndistortKB(const char* configFileName, bool noprefix);
~UndistortKB();
void distortCoordinates(float* in_x, float* in_y, float* out_x, float* out_y, int n) const;
};
}

108
src/util/globalCalib.cpp Normal file
View File

@@ -0,0 +1,108 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#include "util/globalCalib.h"
#include "stdio.h"
#include <iostream>
namespace dso
{
int wG[PYR_LEVELS], hG[PYR_LEVELS];
float fxG[PYR_LEVELS], fyG[PYR_LEVELS],
cxG[PYR_LEVELS], cyG[PYR_LEVELS];
float fxiG[PYR_LEVELS], fyiG[PYR_LEVELS],
cxiG[PYR_LEVELS], cyiG[PYR_LEVELS];
Eigen::Matrix3f KG[PYR_LEVELS], KiG[PYR_LEVELS];
float wM3G;
float hM3G;
void setGlobalCalib(int w, int h,const Eigen::Matrix3f &K)
{
int wlvl=w;
int hlvl=h;
pyrLevelsUsed=1;
while(wlvl%2==0 && hlvl%2==0 && wlvl*hlvl > 5000 && pyrLevelsUsed < PYR_LEVELS)
{
wlvl /=2;
hlvl /=2;
pyrLevelsUsed++;
}
printf("using pyramid levels 0 to %d. coarsest resolution: %d x %d!\n",
pyrLevelsUsed-1, wlvl, hlvl);
if(wlvl>100 && hlvl > 100)
{
printf("\n\n===============WARNING!===================\n "
"using not enough pyramid levels.\n"
"Consider scaling to a resolution that is a multiple of a power of 2.\n");
}
if(pyrLevelsUsed < 3)
{
printf("\n\n===============WARNING!===================\n "
"I need higher resolution.\n"
"I will probably segfault.\n");
}
wM3G = w-3;
hM3G = h-3;
wG[0] = w;
hG[0] = h;
KG[0] = K;
fxG[0] = K(0,0);
fyG[0] = K(1,1);
cxG[0] = K(0,2);
cyG[0] = K(1,2);
KiG[0] = KG[0].inverse();
fxiG[0] = KiG[0](0,0);
fyiG[0] = KiG[0](1,1);
cxiG[0] = KiG[0](0,2);
cyiG[0] = KiG[0](1,2);
for (int level = 1; level < pyrLevelsUsed; ++ level)
{
wG[level] = w >> level;
hG[level] = h >> level;
fxG[level] = fxG[level-1] * 0.5;
fyG[level] = fyG[level-1] * 0.5;
cxG[level] = (cxG[0] + 0.5) / ((int)1<<level) - 0.5;
cyG[level] = (cyG[0] + 0.5) / ((int)1<<level) - 0.5;
KG[level] << fxG[level], 0.0, cxG[level], 0.0, fyG[level], cyG[level], 0.0, 0.0, 1.0; // synthetic
KiG[level] = KG[level].inverse();
fxiG[level] = KiG[level](0,0);
fyiG[level] = KiG[level](1,1);
cxiG[level] = KiG[level](0,2);
cyiG[level] = KiG[level](1,2);
}
}
}

45
src/util/globalCalib.h Normal file
View File

@@ -0,0 +1,45 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/settings.h"
#include "util/NumType.h"
namespace dso
{
extern int wG[PYR_LEVELS], hG[PYR_LEVELS];
extern float fxG[PYR_LEVELS], fyG[PYR_LEVELS],
cxG[PYR_LEVELS], cyG[PYR_LEVELS];
extern float fxiG[PYR_LEVELS], fyiG[PYR_LEVELS],
cxiG[PYR_LEVELS], cyiG[PYR_LEVELS];
extern Eigen::Matrix3f KG[PYR_LEVELS],KiG[PYR_LEVELS];
extern float wM3G;
extern float hM3G;
void setGlobalCalib(int w, int h, const Eigen::Matrix3f &K );
}

382
src/util/globalFuncs.h Normal file
View File

@@ -0,0 +1,382 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "util/settings.h"
#include "util/NumType.h"
#include "IOWrapper/ImageDisplay.h"
#include "fstream"
namespace dso
{
// reads interpolated element from a uchar* array
// SSE2 optimization possible
EIGEN_ALWAYS_INLINE float getInterpolatedElement(const float* const mat, const float x, const float y, const int width)
{
//stats.num_pixelInterpolations++;
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const float* bp = mat +ix+iy*width;
float res = dxdy * bp[1+width]
+ (dy-dxdy) * bp[width]
+ (dx-dxdy) * bp[1]
+ (1-dx-dy+dxdy) * bp[0];
return res;
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement43(const Eigen::Vector4f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector4f* bp = mat +ix+iy*width;
return dxdy * *(const Eigen::Vector3f*)(bp+1+width)
+ (dy-dxdy) * *(const Eigen::Vector3f*)(bp+width)
+ (dx-dxdy) * *(const Eigen::Vector3f*)(bp+1)
+ (1-dx-dy+dxdy) * *(const Eigen::Vector3f*)(bp);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement33(const Eigen::Vector3f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector3f* bp = mat +ix+iy*width;
return dxdy * *(const Eigen::Vector3f*)(bp+1+width)
+ (dy-dxdy) * *(const Eigen::Vector3f*)(bp+width)
+ (dx-dxdy) * *(const Eigen::Vector3f*)(bp+1)
+ (1-dx-dy+dxdy) * *(const Eigen::Vector3f*)(bp);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement33OverAnd(const Eigen::Vector3f* const mat, const bool* overMat, const float x, const float y, const int width, bool& over_out)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector3f* bp = mat +ix+iy*width;
const bool* bbp = overMat +ix+iy*width;
over_out = bbp[1+width] && bbp[1] && bbp[width] && bbp[0];
return dxdy * *(const Eigen::Vector3f*)(bp+1+width)
+ (dy-dxdy) * *(const Eigen::Vector3f*)(bp+width)
+ (dx-dxdy) * *(const Eigen::Vector3f*)(bp+1)
+ (1-dx-dy+dxdy) * *(const Eigen::Vector3f*)(bp);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement33OverOr(const Eigen::Vector3f* const mat, const bool* overMat, const float x, const float y, const int width, bool& over_out)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector3f* bp = mat +ix+iy*width;
const bool* bbp = overMat +ix+iy*width;
over_out = bbp[1+width] || bbp[1] || bbp[width] || bbp[0];
return dxdy * *(const Eigen::Vector3f*)(bp+1+width)
+ (dy-dxdy) * *(const Eigen::Vector3f*)(bp+width)
+ (dx-dxdy) * *(const Eigen::Vector3f*)(bp+1)
+ (1-dx-dy+dxdy) * *(const Eigen::Vector3f*)(bp);
}
EIGEN_ALWAYS_INLINE float getInterpolatedElement31(const Eigen::Vector3f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector3f* bp = mat +ix+iy*width;
return dxdy * (*(const Eigen::Vector3f*)(bp+1+width))[0]
+ (dy-dxdy) * (*(const Eigen::Vector3f*)(bp+width))[0]
+ (dx-dxdy) * (*(const Eigen::Vector3f*)(bp+1))[0]
+ (1-dx-dy+dxdy) * (*(const Eigen::Vector3f*)(bp))[0];
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement13BiLin(const float* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
const float* bp = mat +ix+iy*width;
float tl = *(bp);
float tr = *(bp+1);
float bl = *(bp+width);
float br = *(bp+width+1);
float dx = x - ix;
float dy = y - iy;
float topInt = dx * tr + (1-dx) * tl;
float botInt = dx * br + (1-dx) * bl;
float leftInt = dy * bl + (1-dy) * tl;
float rightInt = dy * br + (1-dy) * tr;
return Eigen::Vector3f(
dx * rightInt + (1-dx) * leftInt,
rightInt-leftInt,
botInt-topInt);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement33BiLin(const Eigen::Vector3f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
const Eigen::Vector3f* bp = mat +ix+iy*width;
float tl = (*(bp))[0];
float tr = (*(bp+1))[0];
float bl = (*(bp+width))[0];
float br = (*(bp+width+1))[0];
float dx = x - ix;
float dy = y - iy;
float topInt = dx * tr + (1-dx) * tl;
float botInt = dx * br + (1-dx) * bl;
float leftInt = dy * bl + (1-dy) * tl;
float rightInt = dy * br + (1-dy) * tr;
return Eigen::Vector3f(
dx * rightInt + (1-dx) * leftInt,
rightInt-leftInt,
botInt-topInt);
}
EIGEN_ALWAYS_INLINE float getInterpolatedElement11Cub(const float* const p, const float x) // for x=0, this returns p[1].
{
return p[1] + 0.5f * x*(p[2] - p[0] + x*(2.0f*p[0] - 5.0f*p[1] + 4.0f*p[2] - p[3] + x*(3.0f*(p[1] - p[2]) + p[3] - p[0])));
}
EIGEN_ALWAYS_INLINE Eigen::Vector2f getInterpolatedElement12Cub(const float* const p, const float x) // for x=0, this returns p[1].
{
float c1 = 0.5f * (p[2] - p[0]);
float c2 = p[0]-2.5f*p[1]+2*p[2]-0.5f*p[3];
float c3 = 0.5f*(3.0f*(p[1]-p[2])+p[3]-p[0]);
float xx = x*x;
float xxx = xx*x;
return Eigen::Vector2f(p[1] + x*c1 + xx*c2 + xxx*c3, c1 + x*2.0f*c2 + xx*3.0f*c3);
}
EIGEN_ALWAYS_INLINE Eigen::Vector2f getInterpolatedElement32Cub(const Eigen::Vector3f* const p, const float x) // for x=0, this returns p[1].
{
float c1 = 0.5f * (p[2][0] - p[0][0]);
float c2 = p[0][0]-2.5f*p[1][0]+2*p[2][0]-0.5f*p[3][0];
float c3 = 0.5f*(3.0f*(p[1][0]-p[2][0])+p[3][0]-p[0][0]);
float xx = x*x;
float xxx = xx*x;
return Eigen::Vector2f(p[1][0] + x*c1 + xx*c2 + xxx*c3, c1 + x*2.0f*c2 + xx*3.0f*c3);
}
EIGEN_ALWAYS_INLINE float getInterpolatedElement11BiCub(const float* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
const float* bp = mat +ix+iy*width;
float val[4];
val[0] =getInterpolatedElement11Cub(bp-width-1, dx);
val[1] =getInterpolatedElement11Cub(bp-1, dx);
val[2] =getInterpolatedElement11Cub(bp+width-1, dx);
val[3] =getInterpolatedElement11Cub(bp+2*width-1, dx);
float dy = y - iy;
return getInterpolatedElement11Cub(val, dy);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement13BiCub(const float* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
const float* bp = mat +ix+iy*width;
float val[4];
float grad[4];
Eigen::Vector2f v = getInterpolatedElement12Cub(bp-width-1, dx);
val[0] = v[0]; grad[0] = v[1];
v = getInterpolatedElement12Cub(bp-1, dx);
val[1] = v[0]; grad[1] = v[1];
v = getInterpolatedElement12Cub(bp+width-1, dx);
val[2] = v[0]; grad[2] = v[1];
v = getInterpolatedElement12Cub(bp+2*width-1, dx);
val[3] = v[0]; grad[3] = v[1];
float dy = y - iy;
v = getInterpolatedElement12Cub(val, dy);
return Eigen::Vector3f(v[0], getInterpolatedElement11Cub(grad, dy), v[1]);
}
EIGEN_ALWAYS_INLINE Eigen::Vector3f getInterpolatedElement33BiCub(const Eigen::Vector3f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
const Eigen::Vector3f* bp = mat +ix+iy*width;
float val[4];
float grad[4];
Eigen::Vector2f v = getInterpolatedElement32Cub(bp-width-1, dx);
val[0] = v[0]; grad[0] = v[1];
v = getInterpolatedElement32Cub(bp-1, dx);
val[1] = v[0]; grad[1] = v[1];
v = getInterpolatedElement32Cub(bp+width-1, dx);
val[2] = v[0]; grad[2] = v[1];
v = getInterpolatedElement32Cub(bp+2*width-1, dx);
val[3] = v[0]; grad[3] = v[1];
float dy = y - iy;
v = getInterpolatedElement12Cub(val, dy);
return Eigen::Vector3f(v[0], getInterpolatedElement11Cub(grad, dy), v[1]);
}
EIGEN_ALWAYS_INLINE Eigen::Vector4f getInterpolatedElement44(const Eigen::Vector4f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector4f* bp = mat +ix+iy*width;
return dxdy * *(bp+1+width)
+ (dy-dxdy) * *(bp+width)
+ (dx-dxdy) * *(bp+1)
+ (1-dx-dy+dxdy) * *(bp);
}
EIGEN_ALWAYS_INLINE Eigen::Vector2f getInterpolatedElement42(const Eigen::Vector4f* const mat, const float x, const float y, const int width)
{
int ix = (int)x;
int iy = (int)y;
float dx = x - ix;
float dy = y - iy;
float dxdy = dx*dy;
const Eigen::Vector4f* bp = mat +ix+iy*width;
return dxdy * *(const Eigen::Vector2f*)(bp+1+width)
+ (dy-dxdy) * *(const Eigen::Vector2f*)(bp+width)
+ (dx-dxdy) * *(const Eigen::Vector2f*)(bp+1)
+ (1-dx-dy+dxdy) * *(const Eigen::Vector2f*)(bp);
}
inline Vec3f makeRainbowf3F(float id)
{
id *= freeDebugParam3;
if(id < 0)
return Vec3f(1,1,1);
int icP = id;
float ifP = id-icP;
icP = icP%3;
if(icP == 0) return Vec3f((1-ifP), ifP, 0);
if(icP == 1) return Vec3f(0, (1-ifP), ifP);
if(icP == 2) return Vec3f(ifP, 0, (1-ifP));
assert(false);
return Vec3f(1,1,1);
}
inline Vec3b makeRainbow3B(float id)
{
id *= freeDebugParam3;
if(!(id > 0))
return Vec3b(255,255,255);
int icP = id;
float ifP = id-icP;
icP = icP%3;
if(icP == 0) return Vec3b(255*(1-ifP), 255*ifP, 0);
if(icP == 1) return Vec3b(0, 255*(1-ifP), 255*ifP);
if(icP == 2) return Vec3b(255*ifP, 0, 255*(1-ifP));
return Vec3b(255,255,255);
}
inline Vec3b makeJet3B(float id)
{
if(id <= 0) return Vec3b(128,0,0);
if(id >= 1) return Vec3b(0,0,128);
int icP = (id*8);
float ifP = (id*8)-icP;
if(icP == 0) return Vec3b(255*(0.5+0.5*ifP), 0, 0);
if(icP == 1) return Vec3b(255, 255*(0.5*ifP), 0);
if(icP == 2) return Vec3b(255, 255*(0.5+0.5*ifP), 0);
if(icP == 3) return Vec3b(255*(1-0.5*ifP), 255, 255*(0.5*ifP));
if(icP == 4) return Vec3b(255*(0.5-0.5*ifP), 255, 255*(0.5+0.5*ifP));
if(icP == 5) return Vec3b(0, 255*(1-0.5*ifP), 255);
if(icP == 6) return Vec3b(0, 255*(0.5-0.5*ifP), 255);
if(icP == 7) return Vec3b(0, 0, 255*(1-0.5*ifP));
return Vec3b(255,255,255);
}
inline Vec3b makeRedGreen3B(float val) // 0 = red, 1=green, 0.5=yellow.
{
if(val < 0) return Vec3b(0,0,255);
else if(val < 0.5) return Vec3b(0,255*2*val,255);
else if(val < 1) return Vec3b(0,255,255-255*2*(val-0.5));
else return Vec3b(0,255,0);
}
}

1412
src/util/nanoflann.h Normal file

File diff suppressed because it is too large Load Diff

314
src/util/settings.cpp Normal file
View File

@@ -0,0 +1,314 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#include "util/settings.h"
#include <boost/bind.hpp>
namespace dso
{
int pyrLevelsUsed = PYR_LEVELS;
/* Parameters controlling when KF's are taken */
float setting_keyframesPerSecond = 0; // if !=0, takes a fixed number of KF per second.
bool setting_realTimeMaxKF = false; // if true, takes as many KF's as possible (will break the system if the camera stays stationary)
float setting_maxShiftWeightT= 0.04f * (640+480);
float setting_maxShiftWeightR= 0.0f * (640+480);
float setting_maxShiftWeightRT= 0.02f * (640+480);
float setting_kfGlobalWeight = 1; // general weight on threshold, the larger the more KF's are taken (e.g., 2 = double the amount of KF's).
float setting_maxAffineWeight= 2;
/* initial hessian values to fix unobservable dimensions / priors on affine lighting parameters.
*/
float setting_idepthFixPrior = 50*50;
float setting_idepthFixPriorMargFac = 600*600;
float setting_initialRotPrior = 1e11;
float setting_initialTransPrior = 1e10;
float setting_initialAffBPrior = 1e14;
float setting_initialAffAPrior = 1e14;
float setting_initialCalibHessian = 5e9;
/* some modes for solving the resulting linear system (e.g. orthogonalize wrt. unobservable dimensions) */
int setting_solverMode = SOLVER_FIX_LAMBDA | SOLVER_ORTHOGONALIZE_X_LATER;
double setting_solverModeDelta = 0.00001;
bool setting_forceAceptStep = true;
/* some thresholds on when to activate / marginalize points */
float setting_minIdepthH_act = 100;
float setting_minIdepthH_marg = 50;
float setting_desiredImmatureDensity = 1500; // immature points per frame
float setting_desiredPointDensity = 2000; // aimed total points in the active window.
float setting_minPointsRemaining = 0.05; // marg a frame if less than X% points remain.
float setting_maxLogAffFacInWindow = 0.7; // marg a frame if factor between intensities to current frame is larger than 1/X or X.
int setting_minFrames = 5; // min frames in window.
int setting_maxFrames = 7; // max frames in window.
int setting_minFrameAge = 1;
int setting_maxOptIterations=6; // max GN iterations.
int setting_minOptIterations=1; // min GN iterations.
float setting_thOptIterations=1.2; // factor on break threshold for GN iteration (larger = break earlier)
/* Outlier Threshold on photometric energy */
float setting_outlierTH = 12*12; // higher -> less strict
float setting_outlierTHSumComponent = 50*50; // higher -> less strong gradient-based reweighting .
int setting_pattern = 8; // point pattern used. DISABLED.
float setting_margWeightFac = 0.5*0.5; // factor on hessian when marginalizing, to account for inaccurate linearization points.
/* when to re-track a frame */
float setting_reTrackThreshold = 1.5; // (larger = re-track more often)
/* require some minimum number of residuals for a point to become valid */
int setting_minGoodActiveResForMarg=3;
int setting_minGoodResForMarg=4;
// 0 = nothing.
// 1 = apply inv. response.
// 2 = apply inv. response & remove V.
int setting_photometricCalibration = 2;
bool setting_useExposure = true;
float setting_affineOptModeA = 1e12; //-1: fix. >=0: optimize (with prior, if > 0).
float setting_affineOptModeB = 1e8; //-1: fix. >=0: optimize (with prior, if > 0).
int setting_gammaWeightsPixelSelect = 1; // 1 = use original intensity for pixel selection; 0 = use gamma-corrected intensity.
float setting_huberTH = 9; // Huber Threshold
// parameters controlling adaptive energy threshold computation.
float setting_frameEnergyTHConstWeight = 0.5;
float setting_frameEnergyTHN = 0.7f;
float setting_frameEnergyTHFacMedian = 1.5;
float setting_overallEnergyTHWeight = 1;
float setting_coarseCutoffTH = 20;
// parameters controlling pixel selection
float setting_minGradHistCut = 0.5;
float setting_minGradHistAdd = 7;
float setting_gradDownweightPerLevel = 0.75;
bool setting_selectDirectionDistribution = true;
/* settings controling initial immature point tracking */
float setting_maxPixSearch = 0.027; // max length of the ep. line segment searched during immature point tracking. relative to image resolution.
float setting_minTraceQuality = 3;
int setting_minTraceTestRadius = 2;
int setting_GNItsOnPointActivation = 3;
float setting_trace_stepsize = 1.0; // stepsize for initial discrete search.
int setting_trace_GNIterations = 3; // max # GN iterations
float setting_trace_GNThreshold = 0.1; // GN stop after this stepsize.
float setting_trace_extraSlackOnTH = 1.2; // for energy-based outlier check, be slightly more relaxed by this factor.
float setting_trace_slackInterval = 1.5; // if pixel-interval is smaller than this, leave it be.
float setting_trace_minImprovementFactor = 2; // if pixel-interval is smaller than this, leave it be.
// for benchmarking different undistortion settings
float benchmarkSetting_fxfyfac = 0;
int benchmarkSetting_width = 0;
int benchmarkSetting_height = 0;
float benchmark_varNoise = 0;
float benchmark_varBlurNoise = 0;
float benchmark_initializerSlackFactor = 1;
int benchmark_noiseGridsize = 3;
float freeDebugParam1 = 1;
float freeDebugParam2 = 1;
float freeDebugParam3 = 1;
float freeDebugParam4 = 1;
float freeDebugParam5 = 1;
bool disableReconfigure=false;
bool debugSaveImages = false;
bool multiThreading = true;
bool disableAllDisplay = false;
bool setting_onlyLogKFPoses = true;
bool setting_logStuff = true;
bool goStepByStep = false;
bool setting_render_displayCoarseTrackingFull=false;
bool setting_render_renderWindowFrames=true;
bool setting_render_plotTrackingFull = false;
bool setting_render_display3D = true;
bool setting_render_displayResidual = true;
bool setting_render_displayVideo = true;
bool setting_render_displayDepth = true;
bool setting_fullResetRequested = false;
bool setting_debugout_runquiet = false;
int sparsityFactor = 5; // not actually a setting, only some legacy stuff for coarse initializer.
void handleKey(char k)
{
char kkk = k;
switch(kkk)
{
case 'd': case 'D':
freeDebugParam5 = ((int)(freeDebugParam5+1))%10;
printf("new freeDebugParam5: %f!\n", freeDebugParam5);
break;
case 's': case 'S':
freeDebugParam5 = ((int)(freeDebugParam5-1+10))%10;
printf("new freeDebugParam5: %f!\n", freeDebugParam5);
break;
}
}
int staticPattern[10][40][2] = {
{{0,0}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, // .
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{0,-1}, {-1,0}, {0,0}, {1,0}, {0,1}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, // +
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{-1,-1}, {1,1}, {0,0}, {-1,1}, {1,-1}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, // x
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{-1,-1}, {-1,0}, {-1,1}, {-1,0}, {0,0}, {0,1}, {1,-1}, {1,0}, {1,1}, {-100,-100}, // full-tight
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{0,-2}, {-1,-1}, {1,-1}, {-2,0}, {0,0}, {2,0}, {-1,1}, {1,1}, {0,2}, {-100,-100}, // full-spread-9
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{0,-2}, {-1,-1}, {1,-1}, {-2,0}, {0,0}, {2,0}, {-1,1}, {1,1}, {0,2}, {-2,-2}, // full-spread-13
{-2,2}, {2,-2}, {2,2}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{-2,-2}, {-2,-1}, {-2,-0}, {-2,1}, {-2,2}, {-1,-2}, {-1,-1}, {-1,-0}, {-1,1}, {-1,2}, // full-25
{-0,-2}, {-0,-1}, {-0,-0}, {-0,1}, {-0,2}, {+1,-2}, {+1,-1}, {+1,-0}, {+1,1}, {+1,2},
{+2,-2}, {+2,-1}, {+2,-0}, {+2,1}, {+2,2}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{0,-2}, {-1,-1}, {1,-1}, {-2,0}, {0,0}, {2,0}, {-1,1}, {1,1}, {0,2}, {-2,-2}, // full-spread-21
{-2,2}, {2,-2}, {2,2}, {-3,-1}, {-3,1}, {3,-1}, {3,1}, {1,-3}, {-1,-3}, {1,3},
{-1,3}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{0,-2}, {-1,-1}, {1,-1}, {-2,0}, {0,0}, {2,0}, {-1,1}, {0,2}, {-100,-100}, {-100,-100}, // 8 for SSE efficiency
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100},
{-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}, {-100,-100}},
{{-4,-4}, {-4,-2}, {-4,-0}, {-4,2}, {-4,4}, {-2,-4}, {-2,-2}, {-2,-0}, {-2,2}, {-2,4}, // full-45-SPREAD
{-0,-4}, {-0,-2}, {-0,-0}, {-0,2}, {-0,4}, {+2,-4}, {+2,-2}, {+2,-0}, {+2,2}, {+2,4},
{+4,-4}, {+4,-2}, {+4,-0}, {+4,2}, {+4,4}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200},
{-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}, {-200,-200}},
};
int staticPatternNum[10] = {
1,
5,
5,
9,
9,
13,
25,
21,
8,
25
};
int staticPatternPadding[10] = {
1,
1,
1,
1,
2,
2,
2,
3,
2,
4
};
}

231
src/util/settings.h Normal file
View File

@@ -0,0 +1,231 @@
/**
* This file is part of DSO.
*
* Copyright 2016 Technical University of Munich and Intel.
* Developed by Jakob Engel <engelj at in dot tum dot de>,
* for more information see <http://vision.in.tum.de/dso>.
* If you use this code, please cite the respective publications as
* listed on the above website.
*
* DSO is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* DSO is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with DSO. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <string.h>
#include <string>
#include <cmath>
namespace dso
{
#define SOLVER_SVD (int)1
#define SOLVER_ORTHOGONALIZE_SYSTEM (int)2
#define SOLVER_ORTHOGONALIZE_POINTMARG (int)4
#define SOLVER_ORTHOGONALIZE_FULL (int)8
#define SOLVER_SVD_CUT7 (int)16
#define SOLVER_REMOVE_POSEPRIOR (int)32
#define SOLVER_USE_GN (int)64
#define SOLVER_FIX_LAMBDA (int)128
#define SOLVER_ORTHOGONALIZE_X (int)256
#define SOLVER_MOMENTUM (int)512
#define SOLVER_STEPMOMENTUM (int)1024
#define SOLVER_ORTHOGONALIZE_X_LATER (int)2048
// ============== PARAMETERS TO BE DECIDED ON COMPILE TIME =================
#define PYR_LEVELS 6
extern int pyrLevelsUsed;
extern float setting_keyframesPerSecond;
extern bool setting_realTimeMaxKF;
extern float setting_maxShiftWeightT;
extern float setting_maxShiftWeightR;
extern float setting_maxShiftWeightRT;
extern float setting_maxAffineWeight;
extern float setting_kfGlobalWeight;
extern float setting_idepthFixPrior;
extern float setting_idepthFixPriorMargFac;
extern float setting_initialRotPrior;
extern float setting_initialTransPrior;
extern float setting_initialAffBPrior;
extern float setting_initialAffAPrior;
extern float setting_initialCalibHessian;
extern int setting_solverMode;
extern double setting_solverModeDelta;
extern float setting_minIdepthH_act;
extern float setting_minIdepthH_marg;
extern float setting_maxIdepth;
extern float setting_maxPixSearch;
extern float setting_desiredImmatureDensity; // done
extern float setting_desiredPointDensity; // done
extern float setting_minPointsRemaining;
extern float setting_maxLogAffFacInWindow;
extern int setting_minFrames;
extern int setting_maxFrames;
extern int setting_minFrameAge;
extern int setting_maxOptIterations;
extern int setting_minOptIterations;
extern float setting_thOptIterations;
extern float setting_outlierTH;
extern float setting_outlierTHSumComponent;
extern int setting_pattern;
extern float setting_margWeightFac;
extern int setting_GNItsOnPointActivation;
extern float setting_minTraceQuality;
extern int setting_minTraceTestRadius;
extern float setting_reTrackThreshold;
extern int setting_minGoodActiveResForMarg;
extern int setting_minGoodResForMarg;
extern int setting_minInlierVotesForMarg;
extern int setting_photometricCalibration;
extern bool setting_useExposure;
extern float setting_affineOptModeA;
extern float setting_affineOptModeB;
extern int setting_gammaWeightsPixelSelect;
extern bool setting_forceAceptStep;
extern float setting_huberTH;
extern bool setting_logStuff;
extern float benchmarkSetting_fxfyfac;
extern int benchmarkSetting_width;
extern int benchmarkSetting_height;
extern float benchmark_varNoise;
extern float benchmark_varBlurNoise;
extern int benchmark_noiseGridsize;
extern float benchmark_initializerSlackFactor;
extern float setting_frameEnergyTHConstWeight;
extern float setting_frameEnergyTHN;
extern float setting_frameEnergyTHFacMedian;
extern float setting_overallEnergyTHWeight;
extern float setting_coarseCutoffTH;
extern float setting_minGradHistCut;
extern float setting_minGradHistAdd;
extern float setting_gradDownweightPerLevel;
extern bool setting_selectDirectionDistribution;
extern float setting_trace_stepsize;
extern int setting_trace_GNIterations;
extern float setting_trace_GNThreshold;
extern float setting_trace_extraSlackOnTH;
extern float setting_trace_slackInterval;
extern float setting_trace_minImprovementFactor;
extern bool setting_render_displayCoarseTrackingFull;
extern bool setting_render_renderWindowFrames;
extern bool setting_render_plotTrackingFull;
extern bool setting_render_display3D;
extern bool setting_render_displayResidual;
extern bool setting_render_displayVideo;
extern bool setting_render_displayDepth;
extern bool setting_fullResetRequested;
extern bool setting_debugout_runquiet;
extern bool disableAllDisplay;
extern bool disableReconfigure;
extern bool setting_onlyLogKFPoses;
extern bool debugSaveImages;
extern int sparsityFactor;
extern bool goStepByStep;
extern bool plotStereoImages;
extern bool multiThreading;
extern float freeDebugParam1;
extern float freeDebugParam2;
extern float freeDebugParam3;
extern float freeDebugParam4;
extern float freeDebugParam5;
void handleKey(char k);
extern int staticPattern[10][40][2];
extern int staticPatternNum[10];
extern int staticPatternPadding[10];
//#define patternNum staticPatternNum[setting_pattern]
//#define patternP staticPattern[setting_pattern]
//#define patternPadding staticPatternPadding[setting_pattern]
//
#define patternNum 8
#define patternP staticPattern[8]
#define patternPadding 2
}