From fed4900a2f2c4809ad5433920d24a5082e30599b Mon Sep 17 00:00:00 2001
From: Sebastian Hahta <joseha@utu.fi>
Date: Wed, 15 Jan 2020 16:50:23 +0200
Subject: [PATCH] Remove unused disparity algorithms

---
 .../src/disparity/optflow_smoothing.cpp       |   1 -
 components/rgbd-sources/CMakeLists.txt        |  24 --
 .../rgbd-sources/include/ftl/offilter.hpp     |  32 --
 .../src/algorithms/consistency.cu             |  53 ---
 .../rgbd-sources/src/algorithms/elas.cpp      |  50 ---
 .../rgbd-sources/src/algorithms/elas.hpp      |  40 --
 .../src/algorithms/fixstars_sgm.cpp           | 239 -----------
 .../src/algorithms/fixstars_sgm.hpp           |  69 ----
 .../rgbd-sources/src/algorithms/nick.cpp      |  41 --
 .../rgbd-sources/src/algorithms/nick.hpp      |  32 --
 .../rgbd-sources/src/algorithms/nick1.cu      | 380 ------------------
 .../rgbd-sources/src/algorithms/opencv_bm.cpp |  34 --
 .../rgbd-sources/src/algorithms/opencv_bm.hpp |  40 --
 .../src/algorithms/opencv_cuda_bm.cpp         |  31 --
 .../src/algorithms/opencv_cuda_bm.hpp         |  42 --
 .../src/algorithms/opencv_cuda_bp.cpp         |  26 --
 .../src/algorithms/opencv_cuda_bp.hpp         |  40 --
 .../src/algorithms/opencv_cuda_csbp.cpp       |   0
 .../src/algorithms/opencv_cuda_csbp.hpp       |   0
 .../src/algorithms/opencv_sgbm.cpp            |  43 --
 .../src/algorithms/opencv_sgbm.hpp            |  40 --
 .../rgbd-sources/src/algorithms/rtcensus.cpp  | 294 --------------
 .../rgbd-sources/src/algorithms/rtcensus.cu   | 205 ----------
 .../rgbd-sources/src/algorithms/rtcensus.hpp  |  64 ---
 .../src/algorithms/rtcensus_sgm.cpp           | 103 -----
 .../src/algorithms/rtcensus_sgm.cu            | 205 ----------
 .../src/algorithms/rtcensus_sgm.hpp           |  60 ---
 .../src/algorithms/sparse_census.cu           |  81 ----
 .../rgbd-sources/src/algorithms/tex_filter.cu | 101 -----
 29 files changed, 2370 deletions(-)
 delete mode 100644 components/rgbd-sources/include/ftl/offilter.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/consistency.cu
 delete mode 100644 components/rgbd-sources/src/algorithms/elas.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/elas.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/nick.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/nick.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/nick1.cu
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_bm.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_bm.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_bm.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_bm.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_bp.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_bp.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_csbp.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_cuda_csbp.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_sgbm.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/opencv_sgbm.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus.cu
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus_sgm.cpp
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus_sgm.cu
 delete mode 100644 components/rgbd-sources/src/algorithms/rtcensus_sgm.hpp
 delete mode 100644 components/rgbd-sources/src/algorithms/sparse_census.cu
 delete mode 100644 components/rgbd-sources/src/algorithms/tex_filter.cu

diff --git a/components/operators/src/disparity/optflow_smoothing.cpp b/components/operators/src/disparity/optflow_smoothing.cpp
index 5304da7dc..efd5d1cc1 100644
--- a/components/operators/src/disparity/optflow_smoothing.cpp
+++ b/components/operators/src/disparity/optflow_smoothing.cpp
@@ -1,7 +1,6 @@
 #include <loguru.hpp>
 
 #include "ftl/operators/disparity.hpp"
-#include "ftl/offilter.hpp"
 #include "disparity/cuda.hpp"
 
 #ifdef HAVE_OPTFLOW
diff --git a/components/rgbd-sources/CMakeLists.txt b/components/rgbd-sources/CMakeLists.txt
index 6027ab17a..b22623bce 100644
--- a/components/rgbd-sources/CMakeLists.txt
+++ b/components/rgbd-sources/CMakeLists.txt
@@ -5,15 +5,10 @@ set(RGBDSRC
 	src/frame.cpp
 	src/frameset.cpp
 	src/sources/stereovideo/stereovideo.cpp
-#	src/sources/middlebury/middlebury_source.cpp
 	src/sources/net/net.cpp
 	src/streamer.cpp
 	src/colour.cpp
 	src/group.cpp
-#	src/algorithms/rtcensus.cpp
-#	src/algorithms/rtcensus_sgm.cpp
-#	src/algorithms/opencv_sgbm.cpp
-#	src/algorithms/opencv_bm.cpp
 	src/cb_segmentation.cpp
 	src/abr.cpp
 	src/sources/virtual/virtual.cpp
@@ -32,24 +27,6 @@ if (LibArchive_FOUND)
 	)
 endif (LibArchive_FOUND)
 
-#if (LIBSGM_FOUND)
-#	list(APPEND RGBDSRC "src/algorithms/fixstars_sgm.cpp")
-#endif (LIBSGM_FOUND)
-
-if (CUDA_FOUND)
-	list(APPEND RGBDSRC
-#		"src/algorithms/opencv_cuda_bm.cpp"
-#		"src/algorithms/opencv_cuda_bp.cpp"
-#		"src/algorithms/rtcensus.cu"
-#		"src/algorithms/rtcensus_sgm.cu"
-#		"src/algorithms/consistency.cu"
-#		"src/algorithms/sparse_census.cu"
-#		"src/algorithms/tex_filter.cu"
-#		"src/algorithms/nick1.cu"
-#		"src/algorithms/nick.cpp")
-)
-endif (CUDA_FOUND)
-
 add_library(ftlrgbd ${RGBDSRC})
 
 # target_compile_options(ftlrgbd PUBLIC $<$<COMPILE_LANGUAGE:CXX>:-fPIC>)
@@ -64,7 +41,6 @@ if (CUDA_FOUND)
 set_property(TARGET ftlrgbd PROPERTY CUDA_SEPARABLE_COMPILATION OFF)
 endif()
 
-#target_include_directories(cv-node PUBLIC ${PROJECT_SOURCE_DIR}/include)
 target_link_libraries(ftlrgbd ftlcommon ${OpenCV_LIBS} ${LIBSGM_LIBRARIES} ${CUDA_LIBRARIES} Eigen3::Eigen ${REALSENSE_LIBRARY} ftlnet ${LibArchive_LIBRARIES} ftlcodecs ftloperators)
 
 add_subdirectory(test)
diff --git a/components/rgbd-sources/include/ftl/offilter.hpp b/components/rgbd-sources/include/ftl/offilter.hpp
deleted file mode 100644
index 0e273d80d..000000000
--- a/components/rgbd-sources/include/ftl/offilter.hpp
+++ /dev/null
@@ -1,32 +0,0 @@
-#pragma once
-
-#include <ftl/config.h>
-#include <ftl/rgbd/frame.hpp>
-
-#ifdef HAVE_OPTFLOW
-#include <ftl/cuda_util.hpp>
-#include <opencv2/core.hpp>
-#include <opencv2/core/cuda.hpp>
-#include <opencv2/cudaoptflow.hpp>
-
-namespace ftl {
-namespace rgbd {
-
-class OFDisparityFilter {
-public:
-	OFDisparityFilter() : n_max_(0), threshold_(0.0) {}
-	OFDisparityFilter(cv::Size size, int n_frames, float threshold);
-	void filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream);
-	void filter(cv::cuda::GpuMat &disp, cv::cuda::GpuMat &optflow, cv::cuda::Stream &stream);
-
-private:
-	int n_max_;
-	float threshold_;
-
-	cv::cuda::GpuMat disp_old_;
-};
-
-}
-}
-
-#endif  // HAVE_OPTFLOW
diff --git a/components/rgbd-sources/src/algorithms/consistency.cu b/components/rgbd-sources/src/algorithms/consistency.cu
deleted file mode 100644
index ca9a3df22..000000000
--- a/components/rgbd-sources/src/algorithms/consistency.cu
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * Algorithms for checking the consistency of two disparity maps.
- */
- 
-#include <ftl/cuda_common.hpp>
-
-#define CONSISTENCY_THRESHOLD	1.0f
-
-/*
- * Check for consistency between the LR and RL disparity maps, only selecting
- * those that are similar. Otherwise it sets the disparity to NAN.
- */
-__global__ void consistency_kernel(cudaTextureObject_t d_sub_l,
-		cudaTextureObject_t d_sub_r, float *disp, int w, int h, int pitch) {
-
-	// TODO This doesn't work at either edge (+-max_disparities)
-	for (STRIDE_Y(v,h)) {
-	for (STRIDE_X(u,w)) {
-		float a = (int)tex2D<float>(d_sub_l, u, v);
-		if (u-a < 0) {
-			disp[v*pitch+u] = NAN; // TODO Check
-			continue;
-		}
-		
-		auto b = tex2D<float>(d_sub_r, u-a, v);
-		
-		if (abs(a-b) <= CONSISTENCY_THRESHOLD) disp[v*pitch+u] = abs((a+b)/2);
-		else disp[v*pitch+u] = NAN;
-	}
-	}
-
-}
-
-namespace ftl {
-namespace cuda {
-	void consistency(const TextureObject<float> &dl, const TextureObject<float> &dr,
-			TextureObject<float> &disp) {
-		dim3 grid(1,1,1);
-    	dim3 threads(128, 1, 1);
-    	grid.x = cv::cuda::device::divUp(disp.width(), 128);
-		grid.y = cv::cuda::device::divUp(disp.height(), 11);
-		consistency_kernel<<<grid, threads>>>(
-			dl.cudaTexture(),
-			dr.cudaTexture(),
-			disp.devicePtr(),
-			disp.width(),
-			disp.height(),
-			disp.pitch() / sizeof(float));
-		cudaSafeCall( cudaGetLastError() );
-	}
-}
-}
-
diff --git a/components/rgbd-sources/src/algorithms/elas.cpp b/components/rgbd-sources/src/algorithms/elas.cpp
deleted file mode 100644
index 07d0de978..000000000
--- a/components/rgbd-sources/src/algorithms/elas.cpp
+++ /dev/null
@@ -1,50 +0,0 @@
-/* Copyright 2019 Nicolas Pope */
-
-#include <ftl/algorithms/elas.hpp>
-#include <loguru.hpp>
-
-#include <chrono>
-
-using ftl::algorithms::ELAS;
-using cv::Mat;
-
-static ftl::Disparity::Register elass("elas", ELAS::create);
-
-ELAS::ELAS(nlohmann::json &config) : Disparity(config) {
-	// TODO(nick) See if these can improve the situation
-	param_.postprocess_only_left = true;
-	param_.disp_min = 0;
-	param_.disp_max = config["maximum"];
-	param_.add_corners = 0;
-	param_.gamma = 3;
-	param_.sradius = 2;
-	param_.match_texture = 1;
-	param_.ipol_gap_width = 3;
-	param_.support_threshold = 0.85;
-	elas_ = new Elas(param_);
-}
-
-void ELAS::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	//Mat left_disp;
-	//Mat right_disp;
-
-	Mat lbw, rbw;
-	cv::cvtColor(l, lbw,  cv::COLOR_BGR2GRAY);
-	cv::cvtColor(r, rbw, cv::COLOR_BGR2GRAY);
-
-	disp = Mat(cv::Size(l.cols, l.rows), CV_32F);
-	Mat dispr(cv::Size(l.cols, l.rows), CV_32F);
-	
-	const int32_t dims[3] = {l.cols,l.rows,static_cast<int32_t>(lbw.step)};
-	
-	if (disp.step/sizeof(float) != lbw.step) LOG(WARNING) << "Incorrect disparity step";
-
-	auto start = std::chrono::high_resolution_clock::now();
-	elas_->process(lbw.data, rbw.data, (float*)disp.data, (float*)dispr.data, dims);
-	std::chrono::duration<double> elapsed =
-			std::chrono::high_resolution_clock::now() - start;
-	LOG(INFO) << "Elas in " << elapsed.count() << "s";
-
-	//disp.convertTo(disp, CV_32F, 1.0f);
-}
-
diff --git a/components/rgbd-sources/src/algorithms/elas.hpp b/components/rgbd-sources/src/algorithms/elas.hpp
deleted file mode 100644
index 29b76cd9e..000000000
--- a/components/rgbd-sources/src/algorithms/elas.hpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_ELAS_HPP_
-#define _FTL_ALGORITHMS_ELAS_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include <elas.h>
-#include <ftl/disparity.hpp>
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * LibELAS - Efficient Large-scale Stereo Matching 
- * @see http://www.cvlibs.net/software/libelas/
- */
-class ELAS : public ftl::Disparity {
-	public:
-	explicit ELAS(nlohmann::json &config);
-
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	/* Factory creator */
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<ELAS>(p, name);
-	}
-
-	private:
-	Elas::parameters param_;
-	Elas *elas_;
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_ELAS_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
deleted file mode 100644
index bbcad8c63..000000000
--- a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
+++ /dev/null
@@ -1,239 +0,0 @@
-/* Copyright 2019 Nicolas Pope */
-
-#include "fixstars_sgm.hpp"
-#include <loguru.hpp>
-#include <opencv2/cudastereo.hpp>
-
-using ftl::algorithms::FixstarsSGM;
-using cv::Mat;
-using cv::cuda::GpuMat;
-using ftl::codecs::Channel;
-using ftl::rgbd::Format;
-
-//static ftl::Disparity::Register fixstarssgm("libsgm", FixstarsSGM::create);
-
-FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) {
-	ssgm_ = nullptr;
-	const int width = size_.width;
-	const int height = size_.height;
-
-	CHECK((width >= 480) && (height >= 360));
-
-	uniqueness_ = value("uniqueness", 0.95f);
-	P1_ = value("P1", 10);
-	P2_ = value("P2", 120);
-
-	CHECK((uniqueness_ >= 0.0) && (uniqueness_ <= 1.0));
-	CHECK(P1_ >= 0);
-	CHECK(P2_ > P1_);
-
-	updateBilateralFilter();
-
-	on("use_filter", [this](const ftl::config::Event&) {
-		updateBilateralFilter();
-	});
-
-	on("filter_radius", [this](const ftl::config::Event&) {
-		updateBilateralFilter();
-	});
-
-	on("filter_iter", [this](const ftl::config::Event&) {
-		updateBilateralFilter();
-	});
-	
-#ifdef HAVE_OPTFLOW
-/*
-	updateOFDisparityFilter();
-
-	on("use_off", [this](const ftl::config::Event&) {
-		updateOFDisparityFilter();
-	});
-
-	on("use_off", [this](const ftl::config::Event&) {
-		updateOFDisparityFilter();
-	});
-*/
-#endif
-
-	init(size_);
-
-	on("uniqueness", [this](const ftl::config::Event&) {
-		float uniqueness = value("uniqueness", uniqueness_);
-		if ((uniqueness >= 0.0) && (uniqueness <= 1.0)) {
-			uniqueness_ = uniqueness;
-			updateParameters();
-		}
-		else {
-			LOG(WARNING) << "invalid uniquness: " << uniqueness;
-		}
-	});
-
-	on("P1", [this](const ftl::config::Event&) {
-		int P1 = value("P1", P1_);
-		if (P1 <= P2_) {
-			P1_ = P1;
-			updateParameters();
-		}
-		else {
-			LOG(WARNING) << "invalid P1: " << P1 << ", (P1 <= P2), P2 is " << P2_;
-		}
-	});
-
-	on("P2", [this](const ftl::config::Event&) {
-		int P2 = value("P2", P2_);
-		if (P2 >= P1_) {
-			P2_ = P2;
-			updateParameters();
-		}
-		else {
-			LOG(WARNING) << "invalid P2: " << P2 << ", (P1 <= P2), P1 is " << P1_;
-		}
-	});
-}
-
-void FixstarsSGM::init(const cv::Size size) {
-	if (ssgm_) { delete ssgm_; }
-	lbw_ = GpuMat(size, CV_8UC1);
-	rbw_ = GpuMat(size, CV_8UC1);
-	dispt_ = GpuMat(size, CV_16SC1);
-
-	ssgm_ = new sgm::StereoSGM(size.width, size.height, max_disp_, 8, 16,
-		lbw_.step, dispt_.step / sizeof(short),
-		sgm::EXECUTE_INOUT_CUDA2CUDA,
-		sgm::StereoSGM::Parameters(P1_, P2_, uniqueness_, true)
-	);
-}
-
-bool FixstarsSGM::updateParameters() {
-	if (ssgm_ == nullptr) { return false; }
-	return this->ssgm_->updateParameters(
-		sgm::StereoSGM::Parameters(P1_, P2_, uniqueness_, true));
-}
-
-bool FixstarsSGM::updateBilateralFilter() {
-	bool enable = value("use_filter", false);
-	int radius = value("filter_radius", 25);
-	int iter = value("filter_iter", 1);
-
-	if (enable) {
-		if (radius <= 0) {
-			LOG(WARNING) << "filter_radius must be greater than 0";
-			enable = false;
-		}
-		if (iter <= 0) {
-			LOG(WARNING) << "filter_iter must be greater than 0";
-			enable = false;
-		}
-	}
-	
-	if (enable) {
-		filter_ = cv::cuda::createDisparityBilateralFilter(max_disp_ << 4, radius, iter);
-		use_filter_ = true;
-	}
-	else {
-		use_filter_ = false;
-	}
-
-	return use_filter_;
-}
-
-#ifdef HAVE_OPTFLOW
-/*
-bool FixstarsSGM::updateOFDisparityFilter() {
-	bool enable = value("use_off", false);
-	int off_size = value("off_size", 9);
-	double off_threshold = value("off_threshold", 0.9);
-
-	if (enable) {
-		if (off_size <= 0) {
-			LOG(WARNING) << "bad off_size: " << off_size;
-			enable = false;
-		}
-
-		if (off_threshold <= 0.0) {
-			LOG(WARNING) << "bad off_threshold: " << off_threshold;
-			enable = false;
-		}
-	}
-	
-	if (enable) {
-		LOG(INFO) << "Optical flow filter, size: " << off_size << ", threshold: " << off_threshold;
-		off_ = ftl::rgbd::OFDisparityFilter(size_, off_size, off_threshold);
-		use_off_ = true;
-	}
-	else {
-		use_off_ = false;
-	}
-	
-	return use_off_;
-}*/
-#endif
-
-void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream)
-{
-	const auto &l = frame.get<GpuMat>(Channel::Left);
-	const auto &r = frame.get<GpuMat>(Channel::Right);
-	auto &disp = frame.create<GpuMat>(Channel::Disparity, Format<float>(l.size()));
-
-	GpuMat l_scaled;
-	if (l.size() != size_)
-	{
-		GpuMat _r;
-		scaleInput(l, r, l_scaled, _r, stream);
-		cv::cuda::cvtColor(l_scaled, lbw_, cv::COLOR_BGR2GRAY, 0, stream);
-		cv::cuda::cvtColor(_r, rbw_, cv::COLOR_BGR2GRAY, 0, stream);
-	}
-	else
-	{
-		cv::cuda::cvtColor(l, lbw_, cv::COLOR_BGR2GRAY, 0, stream);
-		cv::cuda::cvtColor(r, rbw_, cv::COLOR_BGR2GRAY, 0, stream);
-	}
-
-	stream.waitForCompletion();
-	ssgm_->execute(lbw_.data, rbw_.data, dispt_.data);
-	// GpuMat left_pixels(dispt_, cv::Rect(0, 0, max_disp_, dispt_.rows));
-	// left_pixels.setTo(0);
-	cv::cuda::threshold(dispt_, dispt_, 4096.0f, 0.0f, cv::THRESH_TOZERO_INV, stream);
-
-	GpuMat dispt_scaled;
-	if (l.size() != size_)
-	{
-		scaleDisparity(l.size(), dispt_, dispt_scaled, stream);
-	}
-	else
-	{
-		dispt_scaled = dispt_;
-	}
-
-	// TODO: filter could be applied after upscaling (to the upscaled disparity image)
-	if (use_filter_)
-	{
-		filter_->apply(
-			dispt_,
-			l,
-			dispt_,
-			stream
-		);
-	}
-	
-	dispt_scaled.convertTo(disp, CV_32F, 1.0f / 16.0f, stream);
-
-#ifdef HAVE_OPTFLOW
-/*
-	// TODO: Optical flow filter expects CV_32F
-	if (use_off_) {
-		frame.upload(Channel::Flow, stream);
-		stream.waitForCompletion();
-		off_.filter(disp, frame.get<GpuMat>(Channel::Flow), stream);
-	}
-*/
-#endif
-}
-
-void FixstarsSGM::setMask(Mat &mask) {
-	return; // TODO(Nick) Not needed, but also code below does not work with new GPU pipeline
-	CHECK(mask.type() == CV_8UC1) << "mask type must be CV_8U";
-	if (!ssgm_) { init(size_); }
-	mask_l_ = GpuMat(mask);
-	ssgm_->setMask((uint8_t*)mask.data, mask.cols);
-}
\ No newline at end of file
diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
deleted file mode 100644
index 2de1c41ef..000000000
--- a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
-#define _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
-
-#include <ftl/cuda_util.hpp>
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include <opencv2/cudastereo.hpp>
-
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-#include <ftl/config.h>
-
-#include <libsgm.h>
-#include "ftl/offilter.hpp"
-
-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::rgbd::detail::Disparity {
-		public:
-			explicit FixstarsSGM(nlohmann::json &config);
-
-			void compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) override;
-			void setMask(cv::Mat &mask) override;
-
-			/* Factory creator */
-			static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-				return ftl::create<FixstarsSGM>(p, name);
-			}
-
-		private:
-			void init(const cv::Size size);
-			bool updateParameters();
-			bool updateBilateralFilter();
-			#ifdef HAVE_OPTFLOW
-			bool updateOFDisparityFilter();
-			#endif
-
-			float uniqueness_;
-			int P1_;
-			int P2_;
-			bool use_filter_;
-			bool use_off_;
-			cv::Ptr<cv::cuda::DisparityBilateralFilter> filter_;
-			sgm::StereoSGM *ssgm_;
-			cv::cuda::GpuMat lbw_;
-			cv::cuda::GpuMat rbw_;
-			cv::cuda::GpuMat dispt_;
-
-			#ifdef HAVE_OPTFLOW
-			//ftl::rgbd::OFDisparityFilter off_;
-			#endif
-		};
-	};
-};
-
-#endif  // _FTL_ALGORITHMS_FIXSTARS_SGM_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/nick.cpp b/components/rgbd-sources/src/algorithms/nick.cpp
deleted file mode 100644
index 55ccd1db4..000000000
--- a/components/rgbd-sources/src/algorithms/nick.cpp
+++ /dev/null
@@ -1,41 +0,0 @@
-#include "nick.hpp"
-#include <vector_types.h>
-
-using ftl::algorithms::NickCuda;
-using namespace cv;
-using namespace cv::cuda;
-
-static ftl::Disparity::Register nickcuda("nick", NickCuda::create);
-
-NickCuda::NickCuda(nlohmann::json &config) : Disparity(config) {
-
-}
-
-namespace ftl { namespace gpu {
-void nick1_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r, const PtrStepSz<float> &disp, size_t num_disp);
-}}
-
-void NickCuda::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	if (disp_.empty()) disp_ = cuda::GpuMat(l.size(), CV_32FC1);
-	if (left_.empty()) left_ = cuda::GpuMat(l.size(), CV_8UC4);
-	if (right_.empty()) right_ = cuda::GpuMat(l.size(), CV_8UC4);
-	
-	Mat lhsv, rhsv;
-	cv::cvtColor(l, lhsv,  COLOR_BGR2HSV);
-	cv::cvtColor(r, rhsv, COLOR_BGR2HSV);
-	int from_to[] = {0,0,1,1,2,2,-1,3};
-	Mat hsval(lhsv.size(), CV_8UC4);
-	Mat hsvar(rhsv.size(), CV_8UC4);
-	mixChannels(&lhsv, 1, &hsval, 1, from_to, 4);
-	mixChannels(&rhsv, 1, &hsvar, 1, from_to, 4);
-	
-	left_.upload(hsval);
-	right_.upload(hsvar);
-	
-	ftl::gpu::nick1_call(left_, right_, disp_, 200);
-	
-	disp_.download(disp);
-}
-
-
-
diff --git a/components/rgbd-sources/src/algorithms/nick.hpp b/components/rgbd-sources/src/algorithms/nick.hpp
deleted file mode 100644
index 1b5c71ccf..000000000
--- a/components/rgbd-sources/src/algorithms/nick.hpp
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef _FTL_ALGORITHMS_NICK_HPP_
-#define _FTL_ALGORITHMS_NICK_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include <opencv2/cudastereo.hpp>
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-class NickCuda : public ftl::Disparity {
-	public:
-	NickCuda(nlohmann::json &config);
-	
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<NickCuda>(p, name);
-	}
-	
-	private:
-	cv::cuda::GpuMat disp_;
-	//cv::cuda::GpuMat filtered_;
-	cv::cuda::GpuMat left_;
-	cv::cuda::GpuMat right_;
-};
-};
-};
-
-#endif // _FTL_ALGORITHMS_NICK_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/nick1.cu b/components/rgbd-sources/src/algorithms/nick1.cu
deleted file mode 100644
index ab6c0d4bb..000000000
--- a/components/rgbd-sources/src/algorithms/nick1.cu
+++ /dev/null
@@ -1,380 +0,0 @@
-/*
- * Author: Nicolas Pope
- * Based initially on rtcensus
- *
- */
- 
-#include <ftl/cuda_common.hpp>
-#include "../cuda_algorithms.hpp"
-
-using namespace cv::cuda;
-using namespace cv;
-
-
-#define BLOCK_W 60
-#define RADIUS 7
-#define RADIUS2 2
-#define ROWSperTHREAD 1
-
-template <typename T>
-__host__ __device__
-inline T lerp(T v0, T v1, T t) {
-    return fma(t, v1, fma(-t, v0, v0));
-}
-
-#define FILTER_WINDOW 21
-#define FILTER_WINDOW_R	10
-#define EDGE_SENSITIVITY 10.0f
-
-__device__ float calculate_edge_disp(cudaTextureObject_t t, cudaTextureObject_t d, cudaTextureObject_t pT, cudaTextureObject_t pD, uchar4 pixel, int u, int v) {
-	float est = 0.0;
-	int nn = 0;
-	//float pest = 0.0;
-	//int pnn = 0;
-	
-	//cudaTextureObject_t nTex = (pT) ? pT : t;
-	//cudaTextureObject_t nDisp = (pD) ? pD : d;
-
-	for (int m=-FILTER_WINDOW_R; m<=FILTER_WINDOW_R; m++) {
-		for (int n=-FILTER_WINDOW_R; n<=FILTER_WINDOW_R; n++) {
-			uchar4 neigh = tex2D<uchar4>(t, u+n, v+m);
-			float ndisp = tex2D<float>(d,u+n,v+m);
-			
-			//uchar4 pneigh = tex2D<uchar4>(nTex, u+n, v+m);
-			//float pndisp = tex2D<float>(nDisp,u+n,v+m);
-
-			//if (isnan(tex2D<float>(nDisp,u+n,v+m))) continue;
-			//if (m == 0 && n == 0) continue;
-
-			if (!isnan(ndisp) && (abs(neigh.z-pixel.z) <= EDGE_SENSITIVITY)) { // && (isnan(disp) || abs(ndisp-disp) < FILTER_DISP_THRESH)) {
-				est += ndisp;
-				nn++;
-			}
-			
-			//if (!isnan(pndisp) && (abs(pneigh.z-pixel.z) <= EDGE_SENSITIVITY)) { // && (isnan(disp) || abs(ndisp-disp) < FILTER_DISP_THRESH)) {
-			//	pest += pndisp;
-			//	pnn++;
-			//}
-		}	
-	}
-	
-	est = (nn > 0) ? est/nn : NAN;
-	//pest = (pnn > 0) ? pest/pnn : NAN;
-	
-	return est;
-}
-
-__device__ float colour_error(uchar4 v1, uchar4 v2) {
-	float dx = 0.05*abs(v1.x-v2.x);
-	float dy = 0.1*abs(v1.y-v2.y);
-	float dz = 0.85*abs(v1.z-v2.z);
-	return dx + dz + dy;
-}
-
-// TODO Use HUE also and perhaps increase window?
-// Or use more complex notion of texture?
-
-/* Just crossed and currently on edge */
-__device__ bool is_edge_left(uchar4 *line, int x, int n) {
-	if (x < 1 || x >= n-1) return false;
-	return (colour_error(line[x-1],line[x]) > EDGE_SENSITIVITY && colour_error(line[x],line[x+1]) <= EDGE_SENSITIVITY);
-}
-
-/* Just crossed but not on edge now */
-__device__ bool is_edge_right(uchar4 *line, int x, int n) {
-	if (x < 1 || x >= n-1) return false;
-	return (colour_error(line[x-1],line[x]) <= EDGE_SENSITIVITY && colour_error(line[x],line[x+1]) > EDGE_SENSITIVITY);
-}
-
-/*__global__ void filter_kernel(cudaTextureObject_t t, cudaTextureObject_t d,
-		cudaTextureObject_t prevD,
-		cudaTextureObject_t prevT, PtrStepSz<float> f, int num_disp) {
-
-
-	extern __shared__ uchar4 line[]; // One entire line of hsv image
-	
-	for (STRIDE_Y(v,f.rows)) {
-		for (STRIDE_X(u,f.cols)) {
-			line[u] = tex2D<uchar4>(t, u, v);
-		}
-		__syncthreads();
-		
-		for (STRIDE_X(u,f.cols)) {
-			if (is_edge_right(line, u, f.cols)) {
-				float edge_disp = calculate_edge_disp(t,d,prevT,prevD,line[u],u+2,v); // tex2D<float>(d, u, v);
-				f(v,u) = edge_disp;
-				continue;
-				
-				float est = 0.0f;
-				int nn = 0;
-				
-				if (!isnan(edge_disp)) {
-					est += edge_disp;
-					nn++;
-				}
-				//f(v,u) = edge_disp;
-				
-				// TODO, find other edge first to get disparity
-				// Use middle disparities to:
-				//		estimate curve or linear (choose equation)
-				//		or ignore as noise if impossible
-				
-				// TODO For edge disparity, use a window to:
-				//		a) find a missing disparity
-				//		b) make sure disparity has some consensus (above or below mostly)
-				
-				// TODO Use past values?
-				// Another way to fill blanks and gain concensus
-				
-				// TODO Maintain a disparity stack to pop back to background?
-				// Issue of background disparity not being detected.
-				// Only if hsv also matches previous background
-				
-				// TODO Edge prediction (in vertical direction at least) could
-				// help fill both edge and disparity gaps. Propagate disparity
-				// along edges
-				
-				float last_disp = edge_disp;
-				
-				int i;
-				for (i=1; u+i<f.cols; i++) {
-					if (is_edge_right(line, u+i, f.cols)) {
-						//float end_disp = calculate_edge_disp(t,d,prevT,prevD,line[u+i-1],u+i-3,v);
-						//if (!isnan(end_disp)) last_disp = end_disp;
-						break;
-					}
-					
-					float di = tex2D<float>(d,u+i,v);
-					if (!isnan(di)) {
-						est += di;
-						nn++;
-					}
-					//f(v,u+i) = edge_disp;
-				}
-				
-				est = (nn > 0) ? est / nn : NAN;
-				//for (int j=1; j<i; j++) {
-				//	f(v,u+j) = est; //lerp(edge_disp, last_disp, (float)j / (float)(i-1));
-				//}
-			} else f(v,u) = NAN;
-		}
-	}
-}*/
-
-
-__device__ float neighbour_factor(float a, cudaTextureObject_t p, int u, int v) {
-	float f = 1.0f;
-	
-	for (int m=-1; m<=1; m++) {
-		for (int n=-1; n<=1; n++) {
-			float2 neighbour = tex2D<float2>(p, u+n, v+m);
-			if (neighbour.x > 8.0f && abs(neighbour.y-a) < 1.0f) f += neighbour.x / 10.0f;
-		}
-	}
-	
-	return f;
-}
-
-/* Use Prewitt operator */
-__global__ void edge_invar1_kernel(cudaTextureObject_t t, cudaTextureObject_t p, ftl::cuda::TextureObject<float2> o) {
-	for (STRIDE_Y(v,o.height())) {
-		for (STRIDE_X(u,o.width())) {
-			float gx = ((tex2D<uchar4>(t, u-1, v-1).z - tex2D<uchar4>(t, u+1, v-1).z) +
-						(tex2D<uchar4>(t, u-1, v).z - tex2D<uchar4>(t, u+1, v).z) +
-						(tex2D<uchar4>(t, u-1, v+1).z - tex2D<uchar4>(t, u+1, v+1).z)) / 3;
-			float gy = ((tex2D<uchar4>(t, u-1, v-1).z - tex2D<uchar4>(t, u-1, v+1).z) +
-						(tex2D<uchar4>(t, u, v-1).z - tex2D<uchar4>(t, u, v+1).z) +
-						(tex2D<uchar4>(t, u+1, v-1).z - tex2D<uchar4>(t, u+1, v+1).z)) / 3;
-						
-			float g = sqrt(gx*gx+gy*gy);
-			float a = atan2(gy,gx);
-
-			if (g > 1.0f) {
-				float2 n = tex2D<float2>(p, u, v);
-				float avg = (n.x > g && abs(n.y-a) < 0.1f) ? n.x : g;
-				o(u,v) = make_float2(avg,abs(a));
-			} else {
-				o(u,v) = make_float2(NAN,NAN);
-			}
-		}
-	}
-}
-
-__device__ void edge_follow(float &sum, int &count, cudaTextureObject_t i1, int u, int v, int sign) {
-	int u2 = u;
-	int v2 = v;
-	int n = 0;
-	float sumchange = 0.0f;
-	float2 pixel_i1 = tex2D<float2>(i1,u,v);
-
-	for (int j=0; j<5; j++) {
-		// Vertical edge = 0, so to follow it don't move in x
-		int dx = ((pixel_i1.y >= 0.785 && pixel_i1.y <= 2.356) ) ? 0 : 1;
-		int dy = (dx == 1) ? 0 : 1;
-
-		// Check perpendicular to edge to find strongest gradient
-		//if (tex2D<float2>(i1, u2+dy, v2+dx).x < pixel_i1.x && tex2D<float2>(i1, u2-dy, v2-dx).x < pixel_i1.x) {
-			//o(u,v) = pixel_i1.y*81.0f;
-		//} else {
-		//	break;
-		//}
-		//continue;
-		
-		float2 next_pix;
-		next_pix.x = NAN;
-		next_pix.y = NAN;
-		float diff = 10000.0f;
-		int nu, nv;
-		
-		for (int i=-5; i<=5; i++) {
-			float2 pix = tex2D<float2>(i1,u2+dx*i+dy*sign, v2+dy*i+dx*sign);
-			if (isnan(pix.x)) continue;
-			
-			float d = abs(pix.x-pixel_i1.x); //*abs(pix.y-pixel_i1.y);
-			if (d < diff) {
-				nu = u2+dx*i+dy*sign;
-				nv = v2+dy*i+dx*sign;
-				next_pix = pix;
-				diff = d;
-			}
-		}
-		
-		if (!isnan(next_pix.x) && diff < 10.0f) {
-			float change = abs(pixel_i1.y - next_pix.y);
-
-			// Corner or edge change.
-			//if (change > 0.785f) break;
-			if (change > 2.0f) break;
-			
-			sumchange += (nu-u) / (nv-v);
-
-			u2 = nu;
-			v2 = nv;
-			pixel_i1 = next_pix;
-			n++;
-		} else {
-			//o(u,v) = NAN;
-			break;
-		}
-	}
-
-	//if (n == 0) sum = 0.0f;
-	sum = sumchange;
-	count = n;
-}
-
-__global__ void edge_invar2_kernel(cudaTextureObject_t i1, ftl::cuda::TextureObject<float> o) {
-	for (STRIDE_Y(v,o.height())) {
-		for (STRIDE_X(u,o.width())) {
-			float2 pixel_i1 = tex2D<float2>(i1,u,v);
-			
-			if (isnan(pixel_i1.x) || pixel_i1.x < 10.0f) {
-				o(u,v) = NAN;
-				continue;
-			}
-
-			int dx = ((pixel_i1.y >= 0.785 && pixel_i1.y <= 2.356) ) ? 1 : 0;
-			int dy = (dx == 1) ? 0 : 1;
-
-			// Check perpendicular to edge to find strongest gradient
-			if (tex2D<float2>(i1, u+dy, v+dx).x < pixel_i1.x && tex2D<float2>(i1, u-dy, v-dx).x < pixel_i1.x) {
-				//o(u,v) = pixel_i1.y*81.0f;
-			} else {
-				o(u,v) = NAN;
-				continue;
-			}
-
-			float sum_a, sum_b;
-			int count_a, count_b;
-			edge_follow(sum_a, count_a, i1, u, v, 1);
-			edge_follow(sum_b, count_b, i1, u, v, -1);
-			
-
-			// Output curvature of edge
-			if (count_a+count_b > 3) {
-				float curvature = ((sum_a+sum_b) / (float)(count_a+count_b));
-				o(u,v) = curvature * 150.0f + 50.0f;
-				//o(u,v) = (count_a+count_b) * 3.0f;
-				//o(u,v) = pixel_i1.y*81.0f;
-			} else {
-				o(u,v) = NAN;
-			}
-			//o(u,v) = (sumchange / (float)(j-1))*100.0f;
-			
-			// Search in two directions for next edge pixel
-			// Calculate curvature by monitoring gradient angle change
-			// Calculate length by stopping when change exceeds threshold
-		}	
-	}
-}
-
-__global__ void disparity_kernel(cudaTextureObject_t l, cudaTextureObject_t r, ftl::cuda::TextureObject<float> o) {
-	for (STRIDE_Y(v,o.height())) {
-		for (STRIDE_X(u,o.width())) {
-			float dl = tex2D<float>(l,u,v);
-			float dr = tex2D<float>(r,u,v);
-			if (isnan(dl)) o(u,v) = dr;
-			else if (isnan(dr)) o(u,v) = dl;
-			else o(u,v) = max(dl,dr);
-			
-		}
-	}
-}
-
-ftl::cuda::TextureObject<float2> prevEdge1;
-ftl::cuda::TextureObject<float2> prevEdge2;
-ftl::cuda::TextureObject<float> prevDisp;
-ftl::cuda::TextureObject<uchar4> prevImage;
-
-namespace ftl {
-namespace gpu {
-
-void nick1_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r, const PtrStepSz<float> &disp, size_t num_disp) {
-	// Make all the required texture steps
-	// TODO Could reduce re-allocations by caching these
-	ftl::cuda::TextureObject<uchar4> texLeft(l);
-	ftl::cuda::TextureObject<uchar4> texRight(r);
-	ftl::cuda::TextureObject<float2> invl1(l.cols, l.rows);
-	ftl::cuda::TextureObject<float2> invr1(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> invl2(l.cols, l.rows);
-	ftl::cuda::TextureObject<float> invr2(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> output(disp);
-	
-	dim3 grid(1,1,1);
-    dim3 threads(BLOCK_W, 1, 1);
-	grid.x = cv::cuda::device::divUp(l.cols - 2 * RADIUS2, BLOCK_W);
-	grid.y = cv::cuda::device::divUp(l.rows - 2 * RADIUS2, ROWSperTHREAD);
-	
-	edge_invar1_kernel<<<grid,threads>>>(texLeft.cudaTexture(), prevEdge1.cudaTexture(), invl1);
-	cudaSafeCall( cudaGetLastError() );
-	
-	edge_invar1_kernel<<<grid,threads>>>(texRight.cudaTexture(), prevEdge2.cudaTexture(), invr1);
-	cudaSafeCall( cudaGetLastError() );
-	
-	edge_invar2_kernel<<<grid,threads>>>(invl1.cudaTexture(), invl2);
-	cudaSafeCall( cudaGetLastError() );
-	
-	edge_invar2_kernel<<<grid,threads>>>(invr1.cudaTexture(), invr2);
-	cudaSafeCall( cudaGetLastError() );
-	
-	disparity_kernel<<<grid,threads>>>(invl2.cudaTexture(), invr2.cudaTexture(), output);
-	
-	prevEdge1.free();
-	prevEdge1 = invl1;
-	prevEdge2.free();
-	prevEdge2 = invr1;
-	
-	//if (&stream == Stream::Null())
-	cudaSafeCall( cudaDeviceSynchronize() );
-	
-	texLeft.free();
-	texRight.free();
-	//inv1.free();
-	invl2.free();
-	invr2.free();
-	output.free();
-}
-
-}
-}
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_bm.cpp b/components/rgbd-sources/src/algorithms/opencv_bm.cpp
deleted file mode 100644
index e4a840e46..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_bm.cpp
+++ /dev/null
@@ -1,34 +0,0 @@
-#include "opencv_bm.hpp"
-
-using ftl::algorithms::OpenCVBM;
-using namespace cv::ximgproc;
-using namespace cv;
-
-static ftl::Disparity::Register opencvbm("bm", OpenCVBM::create);
-
-OpenCVBM::OpenCVBM(nlohmann::json &config) : Disparity(config) {
-	int wsize = config.value("windows_size", 5);
-	float sigma = config.value("sigma", 1.5);
-	float lambda = config.value("lambda", 8000.0);
-
-	left_matcher_  = StereoBM::create(max_disp_,wsize);
-    wls_filter_ = createDisparityWLSFilter(left_matcher_);
-    right_matcher_ = createRightMatcher(left_matcher_);
-    
-    wls_filter_->setLambda(lambda);
-    wls_filter_->setSigmaColor(sigma);
-}
-
-void OpenCVBM::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	Mat left_disp;
-	Mat right_disp;
-    Mat lg, rg;
-	cv::cvtColor(l, lg, cv::COLOR_BGR2GRAY);
-	cv::cvtColor(r, rg, cv::COLOR_BGR2GRAY);
-	left_matcher_-> compute(lg, rg,left_disp);
-    right_matcher_->compute(rg, lg, right_disp);
-    wls_filter_->filter(left_disp, l, disp, right_disp);
-}
-
-
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_bm.hpp b/components/rgbd-sources/src/algorithms/opencv_bm.hpp
deleted file mode 100644
index 4a6b5af0c..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_bm.hpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_OPENCV_BM_HPP_
-#define _FTL_ALGORITHMS_OPENCV_BM_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include "opencv2/ximgproc.hpp"
-#include <opencv2/calib3d.hpp>
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * OpenCV Block Matching algorithm.
- */
-class OpenCVBM : public ftl::Disparity {
-	public:
-	explicit OpenCVBM(nlohmann::json &config);
-	
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<OpenCVBM>(p, name);
-	}
-	
-	private:
-	cv::Ptr<cv::StereoBM> left_matcher_;
-	cv::Ptr<cv::StereoMatcher> right_matcher_;
-	cv::Ptr<cv::ximgproc::DisparityWLSFilter> wls_filter_;
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_bm.cpp b/components/rgbd-sources/src/algorithms/opencv_cuda_bm.cpp
deleted file mode 100644
index 6261049f0..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_cuda_bm.cpp
+++ /dev/null
@@ -1,31 +0,0 @@
-#include "opencv_cuda_bm.hpp"
-
-using ftl::algorithms::OpenCVCudaBM;
-using namespace cv;
-
-static ftl::Disparity::Register opencvcudabm("cuda_bm", OpenCVCudaBM::create);
-
-OpenCVCudaBM::OpenCVCudaBM(nlohmann::json &config) : Disparity(config) {
-	matcher_ = cuda::createStereoBM(max_disp_);
-	
-	// TODO Add filter
-	filter_ = cv::cuda::createDisparityBilateralFilter(max_disp_, 5, 5);
-}
-
-void OpenCVCudaBM::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	if (disp_.empty()) disp_ = cuda::GpuMat(l.size(), CV_8U);
-	if (filtered_.empty()) filtered_ = cuda::GpuMat(l.size(), CV_8U);
-	if (left_.empty()) left_ = cuda::GpuMat(l.size(), CV_8U);
-	if (right_.empty()) right_ = cuda::GpuMat(l.size(), CV_8U);
-	
-	left_.upload(l);
-	right_.upload(r);
-	
-	matcher_->compute(left_, right_, disp_);
-	filter_->apply(disp_, left_, filtered_);
-	
-	filtered_.download(disp);
-}
-
-
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_bm.hpp b/components/rgbd-sources/src/algorithms/opencv_cuda_bm.hpp
deleted file mode 100644
index 13c88ccd5..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_cuda_bm.hpp
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
-#define _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include <opencv2/cudastereo.hpp>
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * OpenCV CUDA Block Matching algorithm.
- */
-class OpenCVCudaBM : public ftl::Disparity {
-	public:
-	explicit OpenCVCudaBM(nlohmann::json &config);
-	
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<OpenCVCudaBM>(p, name);
-	}
-	
-	private:
-	cv::Ptr<cv::cuda::StereoBM> matcher_;
-	cv::Ptr<cv::cuda::DisparityBilateralFilter> filter_;
-	cv::cuda::GpuMat disp_;
-	cv::cuda::GpuMat filtered_;
-	cv::cuda::GpuMat left_;
-	cv::cuda::GpuMat right_;
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_OPENCV_CUDA_BM_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_bp.cpp b/components/rgbd-sources/src/algorithms/opencv_cuda_bp.cpp
deleted file mode 100644
index ac0eafc50..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_cuda_bp.cpp
+++ /dev/null
@@ -1,26 +0,0 @@
-#include "opencv_cuda_bp.hpp"
-
-using ftl::algorithms::OpenCVCudaBP;
-using namespace cv;
-
-static ftl::Disparity::Register opencvcudabp("cuda_bp", OpenCVCudaBP::create);
-
-OpenCVCudaBP::OpenCVCudaBP(nlohmann::json &config) : Disparity(config) {
-	matcher_ = cuda::createStereoBeliefPropagation(max_disp_);
-	
-	// TODO Add filter
-}
-
-void OpenCVCudaBP::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	if (disp_.empty()) disp_ = cuda::GpuMat(l.size(), CV_8U);
-	if (left_.empty()) left_ = cuda::GpuMat(l.size(), CV_8U);
-	if (right_.empty()) right_ = cuda::GpuMat(l.size(), CV_8U);
-	
-	left_.upload(l);
-	right_.upload(r);
-	
-	matcher_->compute(left_, right_, disp_);
-	
-	disp_.download(disp);
-}
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_bp.hpp b/components/rgbd-sources/src/algorithms/opencv_cuda_bp.hpp
deleted file mode 100644
index 3a498552d..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_cuda_bp.hpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
-#define _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include <opencv2/cudastereo.hpp>
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * OpenCV CUDA Belief Propagation algorithm.
- */
-class OpenCVCudaBP : public ftl::Disparity {
-	public:
-	explicit OpenCVCudaBP(nlohmann::json &config);
-	
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<OpenCVCudaBP>(p, name);
-	}
-	
-	private:
-	cv::Ptr<cv::cuda::StereoBeliefPropagation> matcher_;
-	cv::cuda::GpuMat disp_;
-	cv::cuda::GpuMat left_;
-	cv::cuda::GpuMat right_;
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_OPENCV_CUDA_BP_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_csbp.cpp b/components/rgbd-sources/src/algorithms/opencv_cuda_csbp.cpp
deleted file mode 100644
index e69de29bb..000000000
diff --git a/components/rgbd-sources/src/algorithms/opencv_cuda_csbp.hpp b/components/rgbd-sources/src/algorithms/opencv_cuda_csbp.hpp
deleted file mode 100644
index e69de29bb..000000000
diff --git a/components/rgbd-sources/src/algorithms/opencv_sgbm.cpp b/components/rgbd-sources/src/algorithms/opencv_sgbm.cpp
deleted file mode 100644
index 0d5f0f9e9..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_sgbm.cpp
+++ /dev/null
@@ -1,43 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#include "opencv_sgbm.hpp"
-
-using ftl::algorithms::OpenCVSGBM;
-using cv::Mat;
-
-static ftl::Disparity::Register opencvsgbm("sgbm", OpenCVSGBM::create);
-
-OpenCVSGBM::OpenCVSGBM(nlohmann::json &config) : Disparity(config) {
-	int wsize = config.value("windows_size", 5);
-	float sigma = config.value("sigma", 1.5);
-	float lambda = config.value("lambda", 8000.0);
-
-	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(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);
-}
-
-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, 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_);
-}
-
diff --git a/components/rgbd-sources/src/algorithms/opencv_sgbm.hpp b/components/rgbd-sources/src/algorithms/opencv_sgbm.hpp
deleted file mode 100644
index 4e6437b0f..000000000
--- a/components/rgbd-sources/src/algorithms/opencv_sgbm.hpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
-#define _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include "opencv2/ximgproc.hpp"
-#include <opencv2/calib3d.hpp>
-#include "../disparity.hpp"
-#include <ftl/configuration.hpp>
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * OpenCV Semi Global Matching algorithm.
- */
-class OpenCVSGBM : public ftl::Disparity {
-	public:
-	explicit OpenCVSGBM(nlohmann::json &config);
-	
-	void compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-
-	static inline Disparity *create(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<OpenCVSGBM>(p, name);
-	}
-	
-	private:
-	cv::Ptr<cv::StereoSGBM> left_matcher_;
-	cv::Ptr<cv::StereoMatcher> right_matcher_;
-	cv::Ptr<cv::ximgproc::DisparityWLSFilter> wls_filter_;
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_OPENCV_SGBM_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/rtcensus.cpp b/components/rgbd-sources/src/algorithms/rtcensus.cpp
deleted file mode 100644
index b288045e0..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus.cpp
+++ /dev/null
@@ -1,294 +0,0 @@
-/* Created by Nicolas Pope and Sebastian Hahta
- *
- * Copyright 2019 Nicolas Pope
- *
- * Implementation of algorithm presented in article(s):
- *
- * [1] Humenberger, Engelke, Kubinger: A fast stereo matching algorithm suitable
- *     for embedded real-time systems
- * [2] Humenberger, Zinner, Kubinger: Performance Evaluation of Census-Based
- *     Stereo Matching Algorithm on Embedded and Multi-Core Hardware
- * [3] Humenberger, Engelke, Kubinger: A Census-Based Stereo Vision Algorithm Using Modified Semi-Global Matching
- *     and Plane Fitting to Improve Matching Quality.
- *
- * Equation numbering uses [1] unless otherwise stated
- */
-
-#include <loguru.hpp>
-#include <cmath>
-
-#include <vector>
-#include <tuple>
-#include <bitset>
-#include <chrono>
-
-#include "rtcensus.hpp"
-
-using ftl::algorithms::RTCensus;
-using std::vector;
-using cv::Mat;
-using cv::Point;
-using cv::Size;
-using std::tuple;
-using std::get;
-using std::make_tuple;
-using std::bitset;
-
-/* (8) and (16) */
-#define XHI(P1, P2) ((P1 <= P2) ? 0 : 1)
-
-/* (14) and (15), based on (9) */
-static vector<uint64_t> sparse_census_16x16(const Mat &arr) {
-	vector<uint64_t> result;
-	result.resize(arr.cols*arr.rows, 0);
-
-	/* Loops adapted to avoid edge out-of-bounds checks */
-	for (int v=7; v < arr.rows-7; v++) {
-	for (int u=7; u < arr.cols-7; u++) {
-		uint64_t r = 0;
-
-		/* 16x16 sparse kernel to 8x8 mask (64 bits) */
-		for (int n=-7; n <= 7; n+=2) {
-		auto u_ = u + n;
-		for (int m=-7; m <= 7; m+=2) {
-			auto v_ = v + m;
-			r <<= 1;
-			r |= XHI(arr.at<uint8_t>(v, u), arr.at<uint8_t>(v_, u_));
-		}
-		}
-
-		result[u+v*arr.cols] = r;
-	}
-	}
-
-	return result;
-}
-
-/*
- * (19) note: M and N not the same as in (17), see also (8) in [2].
- * DSI: Disparity Space Image. LTR/RTL matching can be with sign +1/-1
- */
-static void dsi_ca(vector<uint16_t> &result, const vector<uint64_t> &census_R,
-		const vector<uint64_t> &census_L, size_t w, size_t h, size_t d_start,
-		size_t d_stop, int sign = 1) {
-	// TODO(nick) Add asserts
-	assert(census_R.size() == w*h);
-	assert(census_L.size() == w*h);
-	assert(d_stop-d_start > 0);
-
-	auto ds = d_stop - d_start;		// Number of disparities to check
-	result.resize(census_R.size()*ds, 0);
-
-	// Change bounds depending upon disparity direction
-	const size_t eu = (sign > 0) ? w-2-ds : w-2;
-
-	// Adapt bounds to avoid out-of-bounds checks
-	for (size_t v=2; v < h-2; v++) {
-	for (size_t u=(sign > 0) ? 2 : ds+2; u < eu; u++) {
-		const size_t ix = v*w*ds+u*ds;
-
-		// 5x5 window size
-		for (int n=-2; n <= 2; n++) {
-		const auto u_ = u + n;
-		for (int m=-2; m <= 2; m++) {
-			const auto v_ = (v + m)*w;
-			auto r = census_R[u_+v_];
-
-			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
-			}
-		}
-		}
-	}
-	}
-}
-
-/*
- * Find the minimum value in a sub array.
- * TODO This can be removed entirely (see CUDA version)
- */
-static size_t arrmin(vector<uint16_t> &a, size_t ix, size_t len) {
-	uint32_t m = UINT32_MAX;
-	size_t mi = 0;
-	for (size_t i=ix; i < ix+len; i++) {
-		if (a[i] < m) {
-			m = a[i];
-			mi = i;
-		}
-	}
-	return mi-ix;
-}
-
-/*
- * WTA + subpixel disparity (parabilic fitting) (20)
- * TODO remove need to pass tuples (see CUDA version)
- */
-static inline double fit_parabola(tuple<size_t, uint16_t> p,
-		tuple<size_t, uint16_t> pl, tuple<size_t, uint16_t> pr) {
-	double a = get<1>(pr) - get<1>(pl);
-	double b = 2 * (2 * get<1>(p) - get<1>(pl) - get<1>(pr));
-	return static_cast<double>(get<0>(p)) + (a / b);
-}
-
-static cv::Mat d_sub(vector<uint16_t> &dsi, size_t w, size_t h, size_t ds) {
-	Mat result = Mat::zeros(Size(w, h), CV_64FC1);
-
-	assert(dsi.size() == w*h*ds);
-
-	for (size_t v=0; v < h; v++) {
-	const size_t vwds = v * w * ds;
-	for (size_t u=0; u < w; u++) {
-		const size_t uds = u*ds;
-		auto d_min = arrmin(dsi, vwds+uds, ds);
-		double d_sub;
-
-		if (d_min == 0 || d_min == ds-1) {
-			d_sub = d_min;
-		} else {
-			// TODO(nick) Remove use of tuples
-			auto p = make_tuple(d_min, dsi[d_min+vwds+uds]);
-			auto pl = make_tuple(d_min-1, dsi[d_min-1+vwds+uds]);
-			auto pr = make_tuple(d_min+1, dsi[d_min+1+vwds+uds]);
-
-			d_sub = fit_parabola(p, pl, pr);
-		}
-
-		result.at<double>(v, u) = d_sub;
-	}
-	}
-
-	// TODO(nick) Parameter pass not return
-	return result;
-}
-
-/*
- * consistency between LR and RL disparity (23) and (24)
- */
-static cv::Mat consistency(cv::Mat &d_sub_r, cv::Mat &d_sub_l) {
-	size_t w = d_sub_r.cols;
-	size_t h = d_sub_r.rows;
-	Mat result = Mat::zeros(Size(w, h), CV_32FC1);
-
-	for (size_t v=0; v < h; v++) {
-	for (size_t u=0; u < w; u++) {
-		auto a = static_cast<int>(d_sub_l.at<double>(v, u));
-		if (u-a < 0) continue;
-
-		auto b = d_sub_r.at<double>(v, u-a);
-
-		if (std::abs(a-b) <= 1.0) {
-			result.at<float>(v, u) = std::abs((a+b)/2);
-		} else {
-			result.at<float>(v, u) = 0.0f;
-		}
-	}
-	}
-
-	return result;
-}
-
-RTCensus::RTCensus(nlohmann::json &config)
-	:	Disparity(config),
-		gamma_(0.0f),
-		tau_(0.0f),
-		use_cuda_(config.value("use_cuda", true)),
-		alternate_(false) {}
-
-/*
- * Choose the implementation and perform disparity calculation.
- */
-void RTCensus::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	#if defined HAVE_CUDA
-	if (use_cuda_) {
-		computeCUDA(l, r, disp);
-	} else {
-		computeCPU(l, r, disp);
-	}
-	#else  // !HAVE_CUDA
-	computeCPU(l, r, disp);
-	#endif
-}
-
-void RTCensus::computeCPU(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	size_t d_min = min_disp_;
-	size_t d_max = max_disp_;
-
-	Mat lbw, rbw;
-	cv::cvtColor(l, lbw, cv::COLOR_BGR2GRAY);
-	cv::cvtColor(r, rbw, cv::COLOR_BGR2GRAY);
-
-	auto start = std::chrono::high_resolution_clock::now();
-	auto census_R = sparse_census_16x16(rbw);
-	auto census_L = sparse_census_16x16(lbw);
-	std::chrono::duration<double> elapsed =
-			std::chrono::high_resolution_clock::now() - start;
-	LOG(INFO) << "Census in " << elapsed.count() << "s";
-
-	start = std::chrono::high_resolution_clock::now();
-	vector<uint16_t> dsi_ca_R, dsi_ca_L;
-	dsi_ca(dsi_ca_R, census_R, census_L, l.cols, l.rows, d_min, d_max);
-	dsi_ca(dsi_ca_L, census_L, census_R, l.cols, l.rows, d_min, d_max, -1);
-	elapsed = std::chrono::high_resolution_clock::now() - start;
-	LOG(INFO) << "DSI in " << elapsed.count() << "s";
-
-	auto disp_R = d_sub(dsi_ca_R, l.cols, l.rows, d_max-d_min);
-	auto disp_L = d_sub(dsi_ca_L, l.cols, l.rows, d_max-d_min);
-	LOG(INFO) << "Disp done";
-
-	disp = consistency(disp_R, disp_L);
-
-	// TODO(nick) confidence and texture filtering
-}
-
-#if defined HAVE_CUDA
-
-using cv::cuda::PtrStepSz;
-using cv::cuda::GpuMat;
-
-#include <vector_types.h>
-
-namespace ftl { namespace gpu {
-void rtcensus_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r,
-		const PtrStepSz<float> &disp, size_t num_disp, const int &s = 0);
-}}
-
-void RTCensus::computeCUDA(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	// Initialise gpu memory here because we need image size
-	if (disp_.empty()) disp_ = GpuMat(l.size(), CV_32FC1);
-	if (left_.empty()) left_ = GpuMat(l.size(), CV_8UC4);
-	if (left2_.empty()) left2_ = GpuMat(l.size(), CV_8UC4);
-	if (right_.empty()) right_ = GpuMat(l.size(), CV_8UC4);
-
-	Mat lhsv, rhsv;
-	cv::cvtColor(l, lhsv, cv::COLOR_BGR2HSV);
-	cv::cvtColor(r, rhsv, cv::COLOR_BGR2HSV);
-	int from_to[] = {0, 0, 1, 1, 2, 2, -1, 3};
-	Mat hsval(lhsv.size(), CV_8UC4);
-	Mat hsvar(rhsv.size(), CV_8UC4);
-	mixChannels(&lhsv, 1, &hsval, 1, from_to, 4);
-	mixChannels(&rhsv, 1, &hsvar, 1, from_to, 4);
-
-	// Send images to GPU
-	if (alternate_) {
-		left_.upload(hsval);
-	} else {
-		left2_.upload(hsval);
-	}
-	right_.upload(hsvar);
-
-	auto start = std::chrono::high_resolution_clock::now();
-	ftl::gpu::rtcensus_call((alternate_)?left_:left2_, right_, disp_, max_disp_);
-	std::chrono::duration<double> elapsed =
-			std::chrono::high_resolution_clock::now() - start;
-	LOG(INFO) << "CUDA census in " << elapsed.count() << "s";
-
-	alternate_ = !alternate_;
-
-	// Read disparity from GPU
-	disp_.download(disp);
-}
-
-#endif
-
diff --git a/components/rgbd-sources/src/algorithms/rtcensus.cu b/components/rgbd-sources/src/algorithms/rtcensus.cu
deleted file mode 100644
index 6ff8e331e..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus.cu
+++ /dev/null
@@ -1,205 +0,0 @@
-/*
- * Author: Nicolas Pope and Sebastian Hahta (2019)
- * Implementation of algorithm presented in article(s):
- *
- * [1] Humenberger, Engelke, Kubinger: A fast stereo matching algorithm suitable
- *     for embedded real-time systems
- * [2] Humenberger, Zinner, Kubinger: Performance Evaluation of Census-Based
- *     Stereo Matching Algorithm on Embedded and Multi-Core Hardware
- * [3] Humenberger, Engelke, Kubinger: A Census-Based Stereo Vision Algorithm Using Modified Semi-Global Matching
- *     and Plane Fitting to Improve Matching Quality.
- *
- * Equation numbering uses [1] unless otherwise stated
- *
- */
- 
-#include <ftl/cuda_common.hpp>
-#include "../cuda_algorithms.hpp"
-
-using namespace cv::cuda;
-using namespace cv;
-
-
-#define BLOCK_W 60
-#define RADIUS 7
-#define RADIUS2 2
-#define ROWSperTHREAD 1
-
-namespace ftl {
-namespace gpu {
-
-// --- SUPPORT -----------------------------------------------------------------
-
-
-/*
- * Parabolic interpolation between matched disparities either side.
- * Results in subpixel disparity. (20).
- */
-__device__ float fit_parabola(size_t pi, uint16_t p, uint16_t pl, uint16_t pr) {
-	float a = pr - pl;
-	float b = 2 * (2 * p - pl - pr);
-	return static_cast<float>(pi) + (a / b);
-}
-
-// --- KERNELS -----------------------------------------------------------------
-
-/* Convert vector uint2 (32bit x2) into a single uint64_t */
-__forceinline__ __device__ uint64_t uint2asull (uint2 a) {
-	uint64_t res;
-	asm ("mov.b64 %0, {%1,%2};" : "=l"(res) : "r"(a.x), "r"(a.y));
-	return res;
-}
-
-/*
- * Generate left and right disparity images from census data. (18)(19)(25)
- */
-__global__ void disp_kernel(float *disp_l, float *disp_r,
-		int pitchL, int pitchR,
-		size_t width, size_t height,
-		cudaTextureObject_t censusL, cudaTextureObject_t censusR,
-		size_t ds) {	
-	//extern __shared__ uint64_t cache[];
-
-	const int gamma = 35;
-	
-	int u = (blockIdx.x * BLOCK_W) + threadIdx.x + RADIUS2;
-	int v_start = (blockIdx.y * ROWSperTHREAD) + RADIUS2;
-	int v_end = v_start + ROWSperTHREAD;
-	int maxdisp = ds;
-	
-	// Local cache
-	uint64_t l_cache_l1[5][5];
-	uint64_t l_cache_l2[5][5];
-	
-	if (v_end >= height) v_end = height;
-	if (u+maxdisp >= width) maxdisp = width-u;
-	
-	for (int v=v_start; v<v_end; v++) {
-		for (int m=-2; m<=2; m++) {
-			for (int n=-2; n<=2; n++) {
-				l_cache_l2[m+2][n+2] = uint2asull(tex2D<uint2>(censusL,u+n,v+m));
-				l_cache_l1[m+2][n+2] = uint2asull(tex2D<uint2>(censusR,u+n,v+m));
-			}
-		}
-		
-		uint16_t last_ham1 = 65535;
-		uint16_t last_ham2 = 65535;
-		uint16_t min_disp1 = 65535;
-		uint16_t min_disp2 = 65535;
-		uint16_t min_disp1b = 65535;
-		uint16_t min_disp2b = 65535;
-		uint16_t min_before1 = 0;
-		uint16_t min_before2 = 0;
-		uint16_t min_after1 = 0;
-		uint16_t min_after2 = 0;
-		int dix1 = 0;
-		int dix2 = 0;
-		
-		// (19)
-		for (int d=0; d<maxdisp; d++) {
-			uint16_t hamming1 = 0;
-			uint16_t hamming2 = 0;
-			
-			//if (u+2+ds >= width) break;
-		
-			for (int m=-2; m<=2; m++) {
-				const auto v_ = (v + m);
-				for (int n=-2; n<=2; n++) {
-					const auto u_ = u + n;
-					
-					// (18)
-					auto l1 = l_cache_l1[m+2][n+2];
-					auto l2 = l_cache_l2[m+2][n+2];
-					auto r1 = uint2asull(tex2D<uint2>(censusL, u_+d, v_));
-					auto r2 = uint2asull(tex2D<uint2>(censusR, u_-d, v_));
-					hamming1 += __popcll(r1^l1);
-					hamming2 += __popcll(r2^l2);
-				}
-			}
-			
-			// Find the two minimum costs
-			if (hamming1 < min_disp1) {
-				min_before1 = last_ham1;
-				min_disp1 = hamming1;
-				dix1 = d;
-			} else if (hamming1 < min_disp1b) {
-				min_disp1b = hamming1;
-			}
-			if (dix1 == d) min_after1 = hamming1;
-			last_ham1 = hamming1;
-			
-			if (hamming2 < min_disp2) {
-				min_before2 = last_ham2;
-				min_disp2 = hamming2;
-				dix2 = d;
-			} else if (hamming2 < min_disp2b) {
-				min_disp2b = hamming2;
-			}
-			if (dix2 == d) min_after2 = hamming2;
-			last_ham2 = hamming2;
-		
-		}
-		
-		//float d1 = (dix1 == 0 || dix1 == ds-1) ? (float)dix1 : fit_parabola(dix1, min_disp1, min_before1, min_after1);
-		//float d2 = (dix2 == 0 || dix2 == ds-1) ? (float)dix2 : fit_parabola(dix2, min_disp2, min_before2, min_after2);
-	
-		// TODO Allow for discontinuities with threshold
-		// Subpixel disparity (20)
-		float d1 = fit_parabola(dix1, min_disp1, min_before1, min_after1);
-		float d2 = fit_parabola(dix2, min_disp2, min_before2, min_after2);
-	
-		// Confidence filter based on (25)
-		disp_l[v*pitchL+u] = ((min_disp2b - min_disp2) >= gamma) ? d2 : NAN;
-		disp_r[v*pitchR+u] = ((min_disp1b - min_disp1) >= gamma) ? d1 : NAN;
-	}
-}
-
-void rtcensus_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r, const PtrStepSz<float> &disp, size_t num_disp, const int &stream) {
-	// Make all the required texture steps
-	// TODO Could reduce re-allocations by caching these
-	ftl::cuda::TextureObject<uchar4> texLeft(l);
-	ftl::cuda::TextureObject<uchar4> texRight(r);
-	ftl::cuda::TextureObject<uint2> censusTexLeft(l.cols, l.rows);
-	ftl::cuda::TextureObject<uint2> censusTexRight(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> dispTexLeft(l.cols, l.rows);
-	ftl::cuda::TextureObject<float> dispTexRight(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> dispTex(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> output(disp);
-	
-	// Calculate the census for left and right (14)(15)(16)
-	ftl::cuda::sparse_census(texLeft, texRight, censusTexLeft, censusTexRight);
-
-	dim3 grid(1,1,1);
-    dim3 threads(BLOCK_W, 1, 1);
-	grid.x = cv::cuda::device::divUp(l.cols - 2 * RADIUS2, BLOCK_W);
-	grid.y = cv::cuda::device::divUp(l.rows - 2 * RADIUS2, ROWSperTHREAD);
-	
-	// Calculate L and R disparities (18)(19)(20)(21)(22)(25)
-	disp_kernel<<<grid, threads>>>(
-		dispTexLeft.devicePtr(), dispTexRight.devicePtr(),
-		dispTexLeft.pitch()/sizeof(float), dispTexRight.pitch()/sizeof(float),
-		l.cols, l.rows,
-		censusTexLeft.cudaTexture(), censusTexRight.cudaTexture(),
-		num_disp);
-	cudaSafeCall( cudaGetLastError() );
-	
-	// Check consistency between L and R disparities. (23)(24)
-	consistency(dispTexLeft, dispTexRight, dispTex);
-
-	// TM in (7) of paper [3]. Eq (26) in [1] is wrong.
-	texture_filter(texLeft, dispTex, output, num_disp, 10.0);
-
-	cudaSafeCall( cudaDeviceSynchronize() );
-	
-	texLeft.free();
-	texRight.free();
-	censusTexLeft.free();
-	censusTexRight.free();
-	dispTexLeft.free();
-	dispTexRight.free();
-	dispTex.free();
-	output.free();
-}
-
-};
-};
diff --git a/components/rgbd-sources/src/algorithms/rtcensus.hpp b/components/rgbd-sources/src/algorithms/rtcensus.hpp
deleted file mode 100644
index 785af6261..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus.hpp
+++ /dev/null
@@ -1,64 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_RTCENSUS_HPP_
-#define _FTL_ALGORITHMS_RTCENSUS_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include "../disparity.hpp"
-#include <nlohmann/json.hpp>
-
-#include <ftl/config.h>
-#include <ftl/configuration.hpp>
-
-#if defined HAVE_CUDA
-#include <opencv2/core/cuda.hpp>
-#endif
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * Real-time Sparse Census disparity algorithm.
- */
-class RTCensus : public ftl::rgbd::detail::Disparity {
-	public:
-	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(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<RTCensus>(p, name);
-	}
-	
-	private:
-	float gamma_;
-	float tau_;
-	bool use_cuda_;
-	bool alternate_;
-	
-	#if defined HAVE_CUDA
-	cv::cuda::GpuMat disp_;
-	cv::cuda::GpuMat filtered_;
-	cv::cuda::GpuMat left_;
-	cv::cuda::GpuMat left2_;
-	cv::cuda::GpuMat right_;
-	#endif
-	
-	private:
-	void computeCPU(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-	
-	#if defined HAVE_CUDA
-	void computeCUDA(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-	#endif
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_RTCENSUS_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/rtcensus_sgm.cpp b/components/rgbd-sources/src/algorithms/rtcensus_sgm.cpp
deleted file mode 100644
index e84819e60..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus_sgm.cpp
+++ /dev/null
@@ -1,103 +0,0 @@
-/* Created by Nicolas Pope and Sebastian Hahta
- *
- * Implementation of algorithm presented in article(s):
- *
- * [1] Humenberger, Engelke, Kubinger: A fast stereo matching algorithm suitable
- *     for embedded real-time systems
- * [2] Humenberger, Zinner, Kubinger: Performance Evaluation of Census-Based
- *     Stereo Matching Algorithm on Embedded and Multi-Core Hardware
- * [3] Humenberger, Engelke, Kubinger: A Census-Based Stereo Vision Algorithm Using Modified Semi-Global Matching
- *     and Plane Fitting to Improve Matching Quality.
- *
- * Equation numbering uses [1] unless otherwise stated
- */
-
-
-#include "rtcensus_sgm.hpp"
-#include <vector>
-#include <tuple>
-#include <bitset>
-#include <cmath>
-#include <loguru.hpp>
-
-using ftl::algorithms::RTCensusSGM;
-using std::vector;
-using cv::Mat;
-using cv::Point;
-using cv::Size;
-using std::tuple;
-using std::get;
-using std::make_tuple;
-using std::bitset;
-
-//static ftl::Disparity::Register rtcensus("rtcensus_sgm", RTCensusSGM::create);
-
-RTCensusSGM::RTCensusSGM(nlohmann::json &config)
-	:	Disparity(config),
-		gamma_(0.0f),
-		tau_(0.0f),
-		use_cuda_(config.value("use_cuda",true)),
-		alternate_(false) {}
-
-/*
- * Choose the implementation and perform disparity calculation.
- */
-void RTCensusSGM::compute(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	#if defined HAVE_CUDA
-	if (use_cuda_) {
-		computeCUDA(l,r,disp);
-	} else {
-		//computeCPU(l,r,disp);
-		LOG(ERROR) << "RTCensus SGM requires CUDA";
-	}
-	#else // !HAVE_CUDA
-	//computeCPU(l,r,disp);
-	LOG(ERROR) << "RTCensus SGM requires CUDA";
-	#endif
-}
-
-#if defined HAVE_CUDA
-
-using namespace cv::cuda;
-using namespace cv;
-
-#include <vector_types.h>
-
-namespace ftl { namespace gpu {
-void rtcensus_sgm_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r, const PtrStepSz<float> &disp, size_t num_disp, const int &s=0);
-}}
-
-void RTCensusSGM::computeCUDA(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp) {
-	// Initialise gpu memory here because we need image size
-	if (disp_.empty()) disp_ = cuda::GpuMat(l.size(), CV_32FC1);
-	if (left_.empty()) left_ = cuda::GpuMat(l.size(), CV_8UC4);
-	if (left2_.empty()) left2_ = cuda::GpuMat(l.size(), CV_8UC4);
-	if (right_.empty()) right_ = cuda::GpuMat(l.size(), CV_8UC4);
-	
-	Mat lhsv, rhsv;
-	cv::cvtColor(l, lhsv,  COLOR_BGR2HSV);
-	cv::cvtColor(r, rhsv, COLOR_BGR2HSV);
-	int from_to[] = {0,0,1,1,2,2,-1,3};
-	Mat hsval(lhsv.size(), CV_8UC4);
-	Mat hsvar(rhsv.size(), CV_8UC4);
-	mixChannels(&lhsv, 1, &hsval, 1, from_to, 4);
-	mixChannels(&rhsv, 1, &hsvar, 1, from_to, 4);
-	
-	// Send images to GPU
-	if (alternate_) left_.upload(hsval);
-	else left2_.upload(hsval);
-	right_.upload(hsvar);
-
-	auto start = std::chrono::high_resolution_clock::now();
-	ftl::gpu::rtcensus_sgm_call((alternate_)?left_:left2_, right_, disp_, max_disp_);
-	std::chrono::duration<double> elapsed = std::chrono::high_resolution_clock::now() - start;
-	LOG(INFO) << "CUDA rtcensus_sgm in " << elapsed.count() << "s";
-	
-	alternate_ = !alternate_;
-	
-	// Read disparity from GPU
-	disp_.download(disp);
-}
-
-#endif
-
diff --git a/components/rgbd-sources/src/algorithms/rtcensus_sgm.cu b/components/rgbd-sources/src/algorithms/rtcensus_sgm.cu
deleted file mode 100644
index d59a77bc0..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus_sgm.cu
+++ /dev/null
@@ -1,205 +0,0 @@
-/*
- * Author: Nicolas Pope and Sebastian Hahta (2019)
- * Implementation of algorithm presented in article(s):
- *
- * [1] Humenberger, Engelke, Kubinger: A fast stereo matching algorithm suitable
- *     for embedded real-time systems
- * [2] Humenberger, Zinner, Kubinger: Performance Evaluation of Census-Based
- *     Stereo Matching Algorithm on Embedded and Multi-Core Hardware
- * [3] Humenberger, Engelke, Kubinger: A Census-Based Stereo Vision Algorithm Using Modified Semi-Global Matching
- *     and Plane Fitting to Improve Matching Quality.
- *
- * Equation numbering uses [1] unless otherwise stated
- *
- */
- 
-#include <ftl/cuda_common.hpp>
-#include "../cuda_algorithms.hpp"
-
-using namespace cv::cuda;
-using namespace cv;
-
-
-#define BLOCK_W 60
-#define RADIUS 7
-#define RADIUS2 2
-#define ROWSperTHREAD 1
-
-namespace ftl {
-namespace gpu {
-
-// --- SUPPORT -----------------------------------------------------------------
-
-
-/*
- * Parabolic interpolation between matched disparities either side.
- * Results in subpixel disparity. (20).
- */
-__device__ static float fit_parabola(size_t pi, uint16_t p, uint16_t pl, uint16_t pr) {
-	float a = pr - pl;
-	float b = 2 * (2 * p - pl - pr);
-	return static_cast<float>(pi) + (a / b);
-}
-
-// --- KERNELS -----------------------------------------------------------------
-
-/* Convert vector uint2 (32bit x2) into a single uint64_t */
-__forceinline__ __device__ static uint64_t uint2asull (uint2 a) {
-	uint64_t res;
-	asm ("mov.b64 %0, {%1,%2};" : "=l"(res) : "r"(a.x), "r"(a.y));
-	return res;
-}
-
-/*
- * Generate left and right disparity images from census data. (18)(19)(25)
- */
-__global__ static void disp_kernel(float *disp_l, float *disp_r,
-		int pitchL, int pitchR,
-		size_t width, size_t height,
-		cudaTextureObject_t censusL, cudaTextureObject_t censusR,
-		size_t ds) {	
-	//extern __shared__ uint64_t cache[];
-
-	const int gamma = 35;
-	
-	int u = (blockIdx.x * BLOCK_W) + threadIdx.x + RADIUS2;
-	int v_start = (blockIdx.y * ROWSperTHREAD) + RADIUS2;
-	int v_end = v_start + ROWSperTHREAD;
-	int maxdisp = ds;
-	
-	// Local cache
-	uint64_t l_cache_l1[5][5];
-	uint64_t l_cache_l2[5][5];
-	
-	if (v_end >= height) v_end = height;
-	if (u+maxdisp >= width) maxdisp = width-u;
-	
-	for (int v=v_start; v<v_end; v++) {
-		for (int m=-2; m<=2; m++) {
-			for (int n=-2; n<=2; n++) {
-				l_cache_l2[m+2][n+2] = uint2asull(tex2D<uint2>(censusL,u+n,v+m));
-				l_cache_l1[m+2][n+2] = uint2asull(tex2D<uint2>(censusR,u+n,v+m));
-			}
-		}
-		
-		uint16_t last_ham1 = 65535;
-		uint16_t last_ham2 = 65535;
-		uint16_t min_disp1 = 65535;
-		uint16_t min_disp2 = 65535;
-		uint16_t min_disp1b = 65535;
-		uint16_t min_disp2b = 65535;
-		uint16_t min_before1 = 0;
-		uint16_t min_before2 = 0;
-		uint16_t min_after1 = 0;
-		uint16_t min_after2 = 0;
-		int dix1 = 0;
-		int dix2 = 0;
-		
-		// (19)
-		for (int d=0; d<maxdisp; d++) {
-			uint16_t hamming1 = 0;
-			uint16_t hamming2 = 0;
-			
-			//if (u+2+ds >= width) break;
-		
-			for (int m=-2; m<=2; m++) {
-				const auto v_ = (v + m);
-				for (int n=-2; n<=2; n++) {
-					const auto u_ = u + n;
-					
-					// (18)
-					auto l1 = l_cache_l1[m+2][n+2];
-					auto l2 = l_cache_l2[m+2][n+2];
-					auto r1 = uint2asull(tex2D<uint2>(censusL, u_+d, v_));
-					auto r2 = uint2asull(tex2D<uint2>(censusR, u_-d, v_));
-					hamming1 += __popcll(r1^l1);
-					hamming2 += __popcll(r2^l2);
-				}
-			}
-			
-			// Find the two minimum costs
-			if (hamming1 < min_disp1) {
-				min_before1 = last_ham1;
-				min_disp1 = hamming1;
-				dix1 = d;
-			} else if (hamming1 < min_disp1b) {
-				min_disp1b = hamming1;
-			}
-			if (dix1 == d) min_after1 = hamming1;
-			last_ham1 = hamming1;
-			
-			if (hamming2 < min_disp2) {
-				min_before2 = last_ham2;
-				min_disp2 = hamming2;
-				dix2 = d;
-			} else if (hamming2 < min_disp2b) {
-				min_disp2b = hamming2;
-			}
-			if (dix2 == d) min_after2 = hamming2;
-			last_ham2 = hamming2;
-		
-		}
-		
-		//float d1 = (dix1 == 0 || dix1 == ds-1) ? (float)dix1 : fit_parabola(dix1, min_disp1, min_before1, min_after1);
-		//float d2 = (dix2 == 0 || dix2 == ds-1) ? (float)dix2 : fit_parabola(dix2, min_disp2, min_before2, min_after2);
-	
-		// TODO Allow for discontinuities with threshold
-		// Subpixel disparity (20)
-		float d1 = fit_parabola(dix1, min_disp1, min_before1, min_after1);
-		float d2 = fit_parabola(dix2, min_disp2, min_before2, min_after2);
-	
-		// Confidence filter based on (25)
-		disp_l[v*pitchL+u] = ((min_disp2b - min_disp2) >= gamma) ? d2 : NAN;
-		disp_r[v*pitchR+u] = ((min_disp1b - min_disp1) >= gamma) ? d1 : NAN;
-	}
-}
-
-void rtcensus_sgm_call(const PtrStepSz<uchar4> &l, const PtrStepSz<uchar4> &r, const PtrStepSz<float> &disp, size_t num_disp, const int &stream) {
-	// Make all the required texture steps
-	// TODO Could reduce re-allocations by caching these
-	ftl::cuda::TextureObject<uchar4> texLeft(l);
-	ftl::cuda::TextureObject<uchar4> texRight(r);
-	ftl::cuda::TextureObject<uint2> censusTexLeft(l.cols, l.rows);
-	ftl::cuda::TextureObject<uint2> censusTexRight(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> dispTexLeft(l.cols, l.rows);
-	ftl::cuda::TextureObject<float> dispTexRight(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> dispTex(r.cols, r.rows);
-	ftl::cuda::TextureObject<float> output(disp);
-	
-	// Calculate the census for left and right (14)(15)(16)
-	ftl::cuda::sparse_census(texLeft, texRight, censusTexLeft, censusTexRight);
-
-	dim3 grid(1,1,1);
-    dim3 threads(BLOCK_W, 1, 1);
-	grid.x = cv::cuda::device::divUp(l.cols - 2 * RADIUS2, BLOCK_W);
-	grid.y = cv::cuda::device::divUp(l.rows - 2 * RADIUS2, ROWSperTHREAD);
-	
-	// Calculate L and R disparities (18)(19)(20)(21)(22)(25)
-	disp_kernel<<<grid, threads>>>(
-		dispTexLeft.devicePtr(), dispTexRight.devicePtr(),
-		dispTexLeft.pitch()/sizeof(float), dispTexRight.pitch()/sizeof(float),
-		l.cols, l.rows,
-		censusTexLeft.cudaTexture(), censusTexRight.cudaTexture(),
-		num_disp);
-	cudaSafeCall( cudaGetLastError() );
-	
-	// Check consistency between L and R disparities. (23)(24)
-	consistency(dispTexLeft, dispTexRight, dispTex);
-
-	// TM in (7) of paper [3]. Eq (26) in [1] is wrong.
-	texture_filter(texLeft, dispTex, output, num_disp, 10.0);
-
-	cudaSafeCall( cudaDeviceSynchronize() );
-	
-	texLeft.free();
-	texRight.free();
-	censusTexLeft.free();
-	censusTexRight.free();
-	dispTexLeft.free();
-	dispTexRight.free();
-	dispTex.free();
-	output.free();
-}
-
-};
-};
diff --git a/components/rgbd-sources/src/algorithms/rtcensus_sgm.hpp b/components/rgbd-sources/src/algorithms/rtcensus_sgm.hpp
deleted file mode 100644
index ef4dd7fd9..000000000
--- a/components/rgbd-sources/src/algorithms/rtcensus_sgm.hpp
+++ /dev/null
@@ -1,60 +0,0 @@
-/*
- * Copyright 2019 Nicolas Pope
- */
-
-#ifndef _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
-#define _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
-
-#include <opencv2/core.hpp>
-#include <opencv2/opencv.hpp>
-#include "../disparity.hpp"
-#include <nlohmann/json.hpp>
-#include <ftl/configuration.hpp>
-
-#if defined HAVE_CUDA
-#include <opencv2/core/cuda.hpp>
-#endif
-
-namespace ftl {
-namespace algorithms {
-
-/**
- * WORK IN PROGRESS
- */
-class RTCensusSGM : public ftl::rgbd::detail::Disparity {
-	public:
-	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(ftl::Configurable *p, const std::string &name) {
-		return ftl::create<RTCensusSGM>(p, name);
-	}
-	
-	private:
-	float gamma_;
-	float tau_;
-	bool use_cuda_;
-	bool alternate_;
-	
-	#if defined HAVE_CUDA
-	cv::cuda::GpuMat disp_;
-	cv::cuda::GpuMat filtered_;
-	cv::cuda::GpuMat left_;
-	cv::cuda::GpuMat left2_;
-	cv::cuda::GpuMat right_;
-	#endif
-	
-	private:
-	#if defined HAVE_CUDA
-	void computeCUDA(const cv::Mat &l, const cv::Mat &r, cv::Mat &disp);
-	#endif
-};
-};
-};
-
-#endif  // _FTL_ALGORITHMS_RTCENSUSSGM_HPP_
-
diff --git a/components/rgbd-sources/src/algorithms/sparse_census.cu b/components/rgbd-sources/src/algorithms/sparse_census.cu
deleted file mode 100644
index c91235408..000000000
--- a/components/rgbd-sources/src/algorithms/sparse_census.cu
+++ /dev/null
@@ -1,81 +0,0 @@
-/*
- * Author: Nicolas Pope and Sebastian Hahta (2019)
- * Implementation of algorithm presented in article(s):
- *
- * [1] Humenberger, Engelke, Kubinger: A fast stereo matching algorithm suitable
- *     for embedded real-time systems
- * [2] Humenberger, Zinner, Kubinger: Performance Evaluation of Census-Based
- *     Stereo Matching Algorithm on Embedded and Multi-Core Hardware
- *
- * Equation numbering uses [1] unless otherwise stated
- *
- */
-
-#include <ftl/cuda_common.hpp>
-
-#define XHI(P1,P2) ((P1 <= P2) ? 0 : 1)
-
-/*
- * Sparse 16x16 census (so 8x8) creating a 64bit mask
- * (14) & (15), based upon (9)
- */
-__device__ uint64_t _sparse_census(cudaTextureObject_t tex, int u, int v) {
-	uint64_t r = 0;
-
-	unsigned char t = tex2D<uchar4>(tex, u,v).z;
-
-	for (int m=-7; m<=7; m+=2) {
-		//auto start_ix = (v + m)*w + u;
-		for (int n=-7; n<=7; n+=2) {
-			r <<= 1;
-			r |= XHI(t, tex2D<uchar4>(tex, u+n, v+m).z);
-		}
-	}
-
-	return r;
-}
-
-/*
- * Calculate census mask for left and right images together.
- */
-__global__ void census_kernel(cudaTextureObject_t l, cudaTextureObject_t r,
-		int w, int h, uint64_t *censusL, uint64_t *censusR,
-		size_t pL, size_t pR) {	
-	
-	//if (v_end+RADIUS >= h) v_end = h-RADIUS;
-	//if (u+RADIUS >= w) return;
-	
-	for (STRIDE_Y(v,h)) {
-	for (STRIDE_X(u,w)) {
-		//int ix = (u + v*pL);
-		uint64_t cenL = _sparse_census(l, u, v);
-		uint64_t cenR = _sparse_census(r, u, v);
-		
-		censusL[(u + v*pL)] = cenL;
-		censusR[(u + v*pR)] = cenR;
-	}
-	}
-}
-
-namespace ftl {
-namespace cuda {
-	void sparse_census(const TextureObject<uchar4> &l, const TextureObject<uchar4> &r,
-			TextureObject<uint2> &cl, TextureObject<uint2> &cr) {
-		dim3 grid(1,1,1);
-    	dim3 threads(128, 1, 1);
-    	grid.x = cv::cuda::device::divUp(l.width(), 128);
-		grid.y = cv::cuda::device::divUp(l.height(), 11);
-		
-		
-		census_kernel<<<grid, threads>>>(
-			l.cudaTexture(), r.cudaTexture(),
-			l.width(), l.height(),
-			(uint64_t*)cl.devicePtr(), (uint64_t*)cr.devicePtr(),
-			cl.pitch()/sizeof(uint64_t),
-			cr.pitch()/sizeof(uint64_t));
-		cudaSafeCall( cudaGetLastError() );
-	}
-}
-}
-
-
diff --git a/components/rgbd-sources/src/algorithms/tex_filter.cu b/components/rgbd-sources/src/algorithms/tex_filter.cu
deleted file mode 100644
index 12c915726..000000000
--- a/components/rgbd-sources/src/algorithms/tex_filter.cu
+++ /dev/null
@@ -1,101 +0,0 @@
-#include <ftl/cuda_common.hpp>
-
-#define FILTER_WINDOW 11.0
-#define FILTER_WINDOW_R	5
-
-// --- Filter by texture complexity --------------------------------------------
-
-__global__ void texture_filter_kernel(cudaTextureObject_t t, cudaTextureObject_t d,
-		ftl::cuda::TextureObject<float> f, int num_disp, double thresh) { // Thresh = -5000000
-
-	for (STRIDE_Y(v,f.height())) {
-	for (STRIDE_X(u,f.width())) {
-		float disp = tex2D<float>(d,u,v);
-		double neigh_sq = 0.0;
-		double neigh_sum = 0.0;
-
-		for (int m=-FILTER_WINDOW_R; m<=FILTER_WINDOW_R; m++) {
-			for (int n=-FILTER_WINDOW_R; n<=FILTER_WINDOW_R; n++) {
-				uchar4 neigh = tex2D<uchar4>(t, u+n, v+m);
-				neigh_sq += (double)(neigh.z*neigh.z);
-				neigh_sum += (double)neigh.z;
-			}	
-		}
-
-		// Texture map filtering
-		double tm = (neigh_sq / (FILTER_WINDOW*FILTER_WINDOW)) -
-				((neigh_sum / (FILTER_WINDOW*FILTER_WINDOW)) * (neigh_sum / (FILTER_WINDOW*FILTER_WINDOW)));
-
-		if (tm >= thresh) {
-			f(u,v) = disp;
-		} else {
-			f(u,v) = NAN; //(tm <= 200.0) ? 0 : 200.0f;;
-		}
-		
-		//f(u,v) = tm;
-	}
-	}
-}
-
-namespace ftl {
-namespace cuda {
-	void texture_filter(const TextureObject<uchar4> &t, const TextureObject<float> &d,
-			TextureObject<float> &f, int num_disp, double thresh) {
-		dim3 grid(1,1,1);
-    	dim3 threads(128, 1, 1);
-    	grid.x = cv::cuda::device::divUp(d.width(), 128);
-		grid.y = cv::cuda::device::divUp(d.height(), 1);
-		texture_filter_kernel<<<grid, threads>>>(
-			t.cudaTexture(),
-			d.cudaTexture(),
-			f,
-			num_disp,
-			thresh);
-		cudaSafeCall( cudaGetLastError() );
-	}
-}
-}
-
-// --- Generate a texture map --------------------------------------------------
-
-__global__ void texture_map_kernel(cudaTextureObject_t t,
-		ftl::cuda::TextureObject<float> f) {
-
-	for (STRIDE_Y(v,f.height())) {
-	for (STRIDE_X(u,f.width())) {
-		double neigh_sq = 0.0;
-		double neigh_sum = 0.0;
-
-		for (int m=-FILTER_WINDOW_R; m<=FILTER_WINDOW_R; m++) {
-			for (int n=-FILTER_WINDOW_R; n<=FILTER_WINDOW_R; n++) {
-				uchar4 neigh = tex2D<uchar4>(t, u+n, v+m);
-				neigh_sq += (double)(neigh.z*neigh.z);
-				neigh_sum += (double)neigh.z;
-			}	
-		}
-
-		// Texture map filtering
-		double tm = (neigh_sq / (FILTER_WINDOW*FILTER_WINDOW)) -
-				((neigh_sum / (FILTER_WINDOW*FILTER_WINDOW)) * (neigh_sum / (FILTER_WINDOW*FILTER_WINDOW)));
-		
-		f(u,v) = tm;
-	}
-	}
-}
-
-namespace ftl {
-namespace cuda {
-	void texture_map(const TextureObject<uchar4> &t,
-			TextureObject<float> &f) {
-		dim3 grid(1,1,1);
-    	dim3 threads(128, 1, 1);
-    	grid.x = cv::cuda::device::divUp(f.width(), 128);
-		grid.y = cv::cuda::device::divUp(f.height(), 1);
-		texture_map_kernel<<<grid, threads>>>(
-			t.cudaTexture(),
-			f);
-		cudaSafeCall( cudaGetLastError() );
-	}
-}
-}
-
-- 
GitLab