Skip to content
Snippets Groups Projects
Commit ed941999 authored by Nicolas Pope's avatar Nicolas Pope
Browse files

More comments and linting

parent 2410c122
No related branches found
No related tags found
No related merge requests found
Pipeline #9502 passed
Showing
with 241 additions and 65 deletions
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
#define _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
......@@ -8,19 +12,30 @@
namespace ftl {
namespace algorithms {
/**
* Fixstars libSGM stereo matcher.
* @see https://github.com/fixstars/libSGM
*
* NOTE: We are using a modified version that supports disparity of 256.
* @see https://github.com/knicos/libSGM
*/
class FixstarsSGM : public ftl::Disparity {
public:
FixstarsSGM(nlohmann::json &config);
explicit FixstarsSGM(nlohmann::json &config);
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new FixstarsSGM(config); }
/* Factory creator */
static inline Disparity *create(nlohmann::json &config) {
return new FixstarsSGM(config);
}
private:
sgm::StereoSGM *ssgm_;
};
};
};
#endif // _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
#endif // _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
#ifndef _FTL_ALGORITHMS_NP_ATTENTION_HPP_
#define _FTL_ALGORITHMS_NP_ATTENTION_HPP_
namespace ftl {
namespace gpu {
struct AttentionItem {
float factor;
HisteresisTexture<float> source;
}
class Attention {
public:
Attention();
void source(float factor, const HisteresisTexture<float> &ht);
void update();
cudaTextureObject_t cudaTexture();
TextureObject<float> texture();
private:
std::vector<Component> components_;
};
}
}
#endif // _FTL_ALGORITHMS_NP_ATTENTION_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_OPENCV_BM_HPP_
#define _FTL_ALGORITHMS_OPENCV_BM_HPP_
......@@ -9,13 +13,19 @@
namespace ftl {
namespace algorithms {
/**
* OpenCV Block Matching algorithm.
*/
class OpenCVBM : public ftl::Disparity {
public:
OpenCVBM(nlohmann::json &config);
explicit OpenCVBM(nlohmann::json &config);
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new OpenCVBM(config); }
static inline Disparity *create(nlohmann::json &config) {
return new OpenCVBM(config);
}
private:
cv::Ptr<cv::StereoBM> left_matcher_;
......@@ -25,5 +35,5 @@ class OpenCVBM : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
#endif // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
#define _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
......@@ -8,13 +12,19 @@
namespace ftl {
namespace algorithms {
/**
* OpenCV CUDA Block Matching algorithm.
*/
class OpenCVCudaBM : public ftl::Disparity {
public:
OpenCVCudaBM(nlohmann::json &config);
explicit OpenCVCudaBM(nlohmann::json &config);
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new OpenCVCudaBM(config); }
static inline Disparity *create(nlohmann::json &config) {
return new OpenCVCudaBM(config);
}
private:
cv::Ptr<cv::cuda::StereoBM> matcher_;
......@@ -27,5 +37,5 @@ class OpenCVCudaBM : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
#endif // _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
#define _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
......@@ -8,13 +12,19 @@
namespace ftl {
namespace algorithms {
/**
* OpenCV CUDA Belief Propagation algorithm.
*/
class OpenCVCudaBP : public ftl::Disparity {
public:
OpenCVCudaBP(nlohmann::json &config);
explicit OpenCVCudaBP(nlohmann::json &config);
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new OpenCVCudaBP(config); }
static inline Disparity *create(nlohmann::json &config) {
return new OpenCVCudaBP(config);
}
private:
cv::Ptr<cv::cuda::StereoBeliefPropagation> matcher_;
......@@ -25,5 +35,5 @@ class OpenCVCudaBP : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
#endif // _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
#define _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
......@@ -9,9 +13,13 @@
namespace ftl {
namespace algorithms {
/**
* OpenCV Semi Global Matching algorithm.
*/
class OpenCVSGBM : public ftl::Disparity {
public:
OpenCVSGBM(nlohmann::json &config);
explicit OpenCVSGBM(nlohmann::json &config);
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
......@@ -25,5 +33,5 @@ class OpenCVSGBM : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
#endif // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_RTCENSUS_HPP_
#define _FTL_ALGORITHMS_RTCENSUS_HPP_
......@@ -12,16 +16,22 @@
namespace ftl {
namespace algorithms {
/**
* Real-time Sparse Census disparity algorithm.
*/
class RTCensus : public ftl::Disparity {
public:
RTCensus(nlohmann::json &config);
explicit RTCensus(nlohmann::json &config);
void setGamma(float gamma) { gamma_ = gamma; }
void setTau(float tau) { tau_ = tau; }
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new RTCensus(config); }
static inline Disparity *create(nlohmann::json &config) {
return new RTCensus(config);
}
private:
float gamma_;
......@@ -47,5 +57,5 @@ class RTCensus : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_RTCENSUS_HPP_
#endif // _FTL_ALGORITHMS_RTCENSUS_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
#define _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
......@@ -12,16 +16,22 @@
namespace ftl {
namespace algorithms {
/**
* WORK IN PROGRESS
*/
class RTCensusSGM : public ftl::Disparity {
public:
RTCensusSGM(nlohmann::json &config);
explicit RTCensusSGM(nlohmann::json &config);
void setGamma(float gamma) { gamma_ = gamma; }
void setTau(float tau) { tau_ = tau; }
void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
static inline Disparity *create(nlohmann::json &config) { return new RTCensusSGM(config); }
static inline Disparity *create(nlohmann::json &config) {
return new RTCensusSGM(config);
}
private:
float gamma_;
......@@ -45,5 +55,5 @@ class RTCensusSGM : public ftl::Disparity {
};
};
#endif // _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
#endif // _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_CALIBRATION_HPP_
#define _FTL_CALIBRATION_HPP_
......@@ -13,8 +17,16 @@ class FileNode;
};
namespace ftl {
/**
* Manage both performing and applying camera calibration. It will attempt to
* load any existing cached camera calibration unless explicitely told to
* redo the calibration.
*/
class Calibrate {
public:
// TODO(nick) replace or remove this class.
class Settings {
public:
Settings() : goodInput(false) {}
......@@ -68,15 +80,28 @@ class Calibrate {
public:
Calibrate(ftl::LocalSource *s, nlohmann::json &config);
/**
* Perform a new camera calibration. Ignore and replace any existing
* cached calibration.
*/
bool recalibrate();
bool undistort(cv::Mat &l, cv::Mat &r);
bool rectified(cv::Mat &l, cv::Mat &r);
/**
* Get both left and right images from local source, but with intrinsic
* and extrinsic stereo calibration already applied.
*/
bool rectified(cv::Mat &l, cv::Mat &r);
bool isCalibrated();
/**
* Get the camera matrix. Used to convert disparity map back to depth and
* a 3D point cloud.
*/
const cv::Mat &getQ() const { return Q_; }
private:
bool _recalibrate(std::vector<std::vector<cv::Point2f>> *imagePoints,
cv::Mat *cameraMatrix, cv::Mat *distCoeffs, cv::Size *imageSize);
......
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_CUDA_ALGORITHMS_HPP_
#define _FTL_CUDA_ALGORITHMS_HPP_
......@@ -6,15 +10,27 @@
namespace ftl {
namespace cuda {
/**
* Disparity consistency algorithm.
*/
void consistency(const TextureObject<float> &dl, const TextureObject<float> &dr,
TextureObject<float> &disp);
/**
* Calculate the sparse census 16x16 of two stereo images.
*/
void sparse_census(const TextureObject<uchar4> &l, const TextureObject<uchar4> &r,
TextureObject<uint2> &cl, TextureObject<uint2> &cr);
/**
* Filter a disparity image by a texture complexity threshold.
*/
void texture_filter(const TextureObject<uchar4> &t, const TextureObject<float> &d,
TextureObject<float> &f, int num_disp, double thresh);
/**
* Obtain a texture map from a colour image.
*/
void texture_map(const TextureObject<uchar4> &t,
TextureObject<float> &f);
......
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_DISPARITY_HPP_
#define _FTL_DISPARITY_HPP_
......@@ -5,15 +9,29 @@
#include <nlohmann/json.hpp>
namespace ftl {
/**
* Virtual base class for disparity algorithms. An automatic factory is used
* to construct instances of specific algorithms that implement this
* interface, for this to work a static instance of the Register class must
* be created in the algorithms cpp file.
*/
class Disparity {
public:
Disparity(nlohmann::json &config);
explicit Disparity(nlohmann::json &config);
virtual void setMinDisparity(size_t min) { min_disp_ = min; }
virtual void setMaxDisparity(size_t max) { max_disp_ = max; }
/**
* Pure virtual function representing the actual computation of
* disparity from left and right images to be implemented.
*/
virtual void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp)=0;
/**
* Factory registration class.
*/
class Register {
public:
Register(const std::string &n, std::function<Disparity*(nlohmann::json&)> f) {
......@@ -21,6 +39,10 @@ class Disparity {
};
};
/**
* Factory instance creator where config contains an "algorithm" property
* used as the instance name to construct.
*/
static Disparity *create(nlohmann::json &config);
protected:
......
/*
* Copyright 2019 Nicolas Pope
*/
#ifndef _FTL_DISPLAY_HPP_
#define _FTL_DISPLAY_HPP_
#include <ftl/config.h>
#include <nlohmann/json.hpp>
#include <opencv2/opencv.hpp>
#include <ftl/calibrate.hpp>
#include <ftl/config.h>
#include "opencv2/highgui.hpp"
namespace ftl {
class Display {
public:
Display(const Calibrate &cal, nlohmann::json &config);
~Display();
bool render(const cv::Mat &rgb, const cv::Mat &depth);
/**
* Multiple local display options for disparity or point clouds.
*/
class Display {
public:
Display(const Calibrate &cal, nlohmann::json &config);
~Display();
bool render(const cv::Mat &rgb, const cv::Mat &depth);
bool active() const;
bool active() const;
private:
const ftl::Calibrate &calibrate_;
nlohmann::json config_;
private:
const ftl::Calibrate &calibrate_;
nlohmann::json config_;
#if defined HAVE_VIZ
cv::viz::Viz3d *window_;
#endif // HAVE_VIZ
#if defined HAVE_VIZ
cv::viz::Viz3d *window_;
#endif // HAVE_VIZ
bool active_;
};
bool active_;
};
};
#endif // _FTL_DISPLAY_HPP_
#endif // _FTL_DISPLAY_HPP_
/*
* Copyright 2019 Nicolas Pope
*/
#include <ftl/algorithms/opencv_sgbm.hpp>
using ftl::algorithms::OpenCVSGBM;
using namespace cv::ximgproc;
using namespace cv;
using cv::Mat;
static ftl::Disparity::Register opencvsgbm("sgbm", OpenCVSGBM::create);
......@@ -11,15 +14,15 @@ OpenCVSGBM::OpenCVSGBM(nlohmann::json &config) : Disparity(config) {
float sigma = config.value("sigma", 1.5);
float lambda = config.value("lambda", 8000.0);
left_matcher_ = StereoSGBM::create(min_disp_,max_disp_,wsize);
left_matcher_ = cv::StereoSGBM::create(min_disp_, max_disp_, wsize);
left_matcher_->setP1(24*wsize*wsize);
left_matcher_->setP2(96*wsize*wsize);
left_matcher_->setPreFilterCap(63);
left_matcher_->setMode(StereoSGBM::MODE_SGBM_3WAY);
left_matcher_->setMinDisparity(config.value("minimum",0));
wls_filter_ = createDisparityWLSFilter(left_matcher_);
right_matcher_ = createRightMatcher(left_matcher_);
left_matcher_->setMode(cv::StereoSGBM::MODE_SGBM_3WAY);
left_matcher_->setMinDisparity(config.value("minimum", 0));
wls_filter_ = cv::ximgproc::createDisparityWLSFilter(left_matcher_);
right_matcher_ = cv::ximgproc::createRightMatcher(left_matcher_);
wls_filter_->setLambda(lambda);
wls_filter_->setSigmaColor(sigma);
}
......@@ -28,15 +31,13 @@ void OpenCVSGBM::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
Mat lbw, rbw;
Mat left_disp;
Mat right_disp;
cv::cvtColor(l, lbw, COLOR_BGR2GRAY);
cv::cvtColor(r, rbw, COLOR_BGR2GRAY);
left_matcher_-> compute(lbw, rbw,left_disp);
right_matcher_->compute(rbw,lbw, right_disp);
wls_filter_->filter(left_disp,l,disp,right_disp);
cv::cvtColor(l, lbw, cv::COLOR_BGR2GRAY);
cv::cvtColor(r, rbw, cv::COLOR_BGR2GRAY);
left_matcher_-> compute(lbw, rbw, left_disp);
right_matcher_->compute(rbw, lbw, right_disp);
wls_filter_->filter(left_disp, l, disp, right_disp);
// WHY 12!!!!!!
disp.convertTo(disp, CV_32F, 12.0 / max_disp_);
}
......@@ -14,17 +14,16 @@
* Equation numbering uses [1] unless otherwise stated
*/
#include <ftl/algorithms/rtcensus.hpp>
#include <cmath>
#include <glog/logging.h>
#include <cmath>
#include <vector>
#include <tuple>
#include <bitset>
#include <chrono>
#include <ftl/algorithms/rtcensus.hpp>
using ftl::algorithms::RTCensus;
using std::vector;
using cv::Mat;
......@@ -100,7 +99,7 @@ static void dsi_ca(vector<uint16_t> &result, const vector<uint64_t> &census_R,
for (size_t d=0; d < ds; d++) {
const auto d_ = d * sign;
auto l = census_L[v_+(u_+d_)];
result[ix+d] += bitset<64>(r^l).count(); // Hamming distance
result[ix+d] += bitset<64>(r^l).count(); // Hamming distance
}
}
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment