diff --git a/CMakeLists.txt b/CMakeLists.txt
index 95530e23a154175eac8a303897f73a91fe6432f5..65b3fb9c01a1db2aaf46f59ae9fdfd67024fcfce 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -175,7 +175,7 @@ check_include_file_cxx("opencv2/cudastereo.hpp" HAVE_OPENCVCUDA)
 find_program(CPPCHECK_FOUND cppcheck)
 if (CPPCHECK_FOUND)
 	message(STATUS "Found cppcheck: will perform source checks")
-	set(CMAKE_CXX_CPPCHECK "cppcheck" "--enable=warning,performance,portability,style" "--inline-suppr" "--std=c++11" "--suppress=*:*catch.hpp" "--suppress=*:*elas*" "--suppress=*:*nanogui*" "--suppress=*:*json.hpp" "--quiet")
+	set(CMAKE_CXX_CPPCHECK "cppcheck" "-D__align__(A)" "-DCUDARTAPI" "--enable=warning,performance,portability,style" "--inline-suppr" "--std=c++11" "--suppress=*:*catch.hpp" "--suppress=*:*elas*" "--suppress=*:*nanogui*" "--suppress=*:*json.hpp" "--quiet")
 endif()
 
 # include_directories(${PROJECT_SOURCE_DIR}/common/cpp/include)
diff --git a/applications/groupview/src/main.cpp b/applications/groupview/src/main.cpp
index d1dab2607ce15ea1ec5defe63aa4ff2b48ee95b6..99820d759b6c2ef6be37e34e6efea157295c0104 100644
--- a/applications/groupview/src/main.cpp
+++ b/applications/groupview/src/main.cpp
@@ -16,6 +16,7 @@ using std::string;
 using std::vector;
 using cv::Size;
 using cv::Mat;
+using ftl::rgbd::Channel;
 
 // TODO: remove code duplication (function from reconstruction)
 static void from_json(nlohmann::json &json, map<string, Matrix4d> &transformations) {
@@ -79,7 +80,7 @@ void modeLeftRight(ftl::Configurable *root) {
 	ftl::rgbd::Group group;
 
 	for (auto* src : sources) {
-		src->setChannel(ftl::rgbd::kChanRight);
+		src->setChannel(Channel::Right);
 		group.addSource(src);
 	}
 
@@ -91,8 +92,8 @@ void modeLeftRight(ftl::Configurable *root) {
 		mutex.lock();
 		bool good = true;
 		for (size_t i = 0; i < frames.frames.size(); i ++) {
-			auto &chan1 = frames.frames[i].getChannel<cv::Mat>(ftl::rgbd::kChanColour);
-			auto &chan2 = frames.frames[i].getChannel<cv::Mat>(frames.sources[i]->getChannel());
+			auto &chan1 = frames.frames[i].get<cv::Mat>(Channel::Colour);
+			auto &chan2 = frames.frames[i].get<cv::Mat>(frames.sources[i]->getChannel());
 			if (chan1.empty()) good = false;
 			if (chan2.empty()) good = false;
 			if (chan1.channels() != 3) good = false; // ASSERT
@@ -166,7 +167,7 @@ void modeFrame(ftl::Configurable *root, int frames=1) {
 		} else {
 			s->setPose(T->second);
 		}
-		s->setChannel(ftl::rgbd::kChanDepth);
+		s->setChannel(Channel::Depth);
 		group.addSource(s);
 	}
 
@@ -185,8 +186,8 @@ void modeFrame(ftl::Configurable *root, int frames=1) {
 		std::vector<cv::Mat> frames;
 
 		for (size_t i=0; i<fs.sources.size(); ++i) {
-			auto &chan1 = fs.frames[i].getChannel<cv::Mat>(ftl::rgbd::kChanColour);
-			auto &chan2 = fs.frames[i].getChannel<cv::Mat>(fs.sources[i]->getChannel());
+			auto &chan1 = fs.frames[i].get<cv::Mat>(Channel::Colour);
+			auto &chan2 = fs.frames[i].get<cv::Mat>(fs.sources[i]->getChannel());
 			if (chan1.empty() || chan2.empty()) return true;
 
 			frames.push_back(chan1);
@@ -213,8 +214,8 @@ void modeFrame(ftl::Configurable *root, int frames=1) {
 			auto writer = ftl::rgbd::SnapshotWriter(std::string(timestamp) + ".tar.gz");
 
 			for (size_t i=0; i<fs.sources.size(); ++i) {
-				auto &chan1 = fs.frames[i].getChannel<cv::Mat>(ftl::rgbd::kChanColour);
-				auto &chan2 = fs.frames[i].getChannel<cv::Mat>(fs.sources[i]->getChannel());
+				auto &chan1 = fs.frames[i].get<cv::Mat>(Channel::Colour);
+				auto &chan2 = fs.frames[i].get<cv::Mat>(fs.sources[i]->getChannel());
 
 				writer.addSource(fs.sources[i]->getURI(), fs.sources[i]->parameters(), fs.sources[i]->getPose());
 				//LOG(INFO) << "SAVE: " << fs.channel1[i].cols << ", " << fs.channel2[i].type();
@@ -258,7 +259,7 @@ void modeVideo(ftl::Configurable *root) {
 	auto sources = ftl::createArray<ftl::rgbd::Source>(root, "sources", net);
 	const string path = root->value<string>("save_to", "./");
 
-	for (auto* src : sources) { src->setChannel(ftl::rgbd::kChanDepth); }
+	for (auto* src : sources) { src->setChannel(Channel::Depth); }
 
 	cv::Mat show;
 	vector<cv::Mat> rgb(sources.size());
diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp
index f44521b3a81d06a4087a56a8eacf6d2bf4d4700b..dd8bc936a6e06ac7a15e2951a053eeadb783b43f 100644
--- a/applications/gui/src/camera.cpp
+++ b/applications/gui/src/camera.cpp
@@ -7,6 +7,8 @@
 using ftl::rgbd::isValidDepth;
 using ftl::gui::GLTexture;
 using ftl::gui::PoseWindow;
+using ftl::rgbd::Channel;
+using ftl::rgbd::Channels;
 
 // TODO(Nick) MOVE
 class StatisticsImage {
@@ -133,10 +135,10 @@ ftl::gui::Camera::Camera(ftl::gui::Screen *screen, ftl::rgbd::Source *src) : scr
 	ftime_ = (float)glfwGetTime();
 	pause_ = false;
 
-	channel_ = ftl::rgbd::kChanLeft;
+	channel_ = Channel::Left;
 
-	channels_.push_back(ftl::rgbd::kChanLeft);
-	channels_.push_back(ftl::rgbd::kChanDepth);
+	channels_ += Channel::Left;
+	channels_ += Channel::Depth;
 
 	// Create pose window...
 	posewin_ = new PoseWindow(screen, src_->getURI());
@@ -227,27 +229,27 @@ void ftl::gui::Camera::showSettings() {
 
 }
 
-void ftl::gui::Camera::setChannel(ftl::rgbd::channel_t c) {
+void ftl::gui::Camera::setChannel(Channel c) {
 	channel_ = c;
 	switch (c) {
-	case ftl::rgbd::kChanEnergy:
-	case ftl::rgbd::kChanFlow:
-	case ftl::rgbd::kChanConfidence:
-	case ftl::rgbd::kChanNormals:
-	case ftl::rgbd::kChanRight:
+	case Channel::Energy:
+	case Channel::Flow:
+	case Channel::Confidence:
+	case Channel::Normals:
+	case Channel::Right:
 		src_->setChannel(c);
 		break;
 
-	case ftl::rgbd::kChanDeviation:
+	case Channel::Deviation:
 		if (stats_) { stats_->reset(); }
-		src_->setChannel(ftl::rgbd::kChanDepth);
+		src_->setChannel(Channel::Depth);
 		break;
 	
-	case ftl::rgbd::kChanDepth:
+	case Channel::Depth:
 		src_->setChannel(c);
 		break;
 	
-	default: src_->setChannel(ftl::rgbd::kChanNone);
+	default: src_->setChannel(Channel::None);
 	}
 }
 
@@ -320,7 +322,7 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 
 		// When switching from right to depth, client may still receive
 		// right images from previous batch (depth.channels() == 1 check)
-		if (channel_ == ftl::rgbd::kChanDeviation &&
+		if (channel_ == Channel::Deviation &&
 			depth_.rows > 0 && depth_.channels() == 1)
 		{
 			if (!stats_) {
@@ -333,19 +335,19 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 		cv::Mat tmp;
 
 		switch(channel_) {
-			case ftl::rgbd::kChanEnergy:
+			case Channel::Energy:
 				if (depth_.rows == 0) { break; }
 				visualizeEnergy(depth_, tmp, 10.0);
 				texture_.update(tmp);
 				break;
-			case ftl::rgbd::kChanDepth:
+			case Channel::Depth:
 				if (depth_.rows == 0) { break; }
 				visualizeDepthMap(depth_, tmp, 7.0);
 				if (screen_->root()->value("showEdgesInDepth", false)) drawEdges(rgb_, tmp);
 				texture_.update(tmp);
 				break;
 			
-			case ftl::rgbd::kChanDeviation:
+			case Channel::Deviation:
 				if (depth_.rows == 0) { break; }
 				//imageSize = Vector2f(depth.cols, depth.rows);
 				stats_->getStdDev(tmp);
@@ -354,10 +356,10 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 				texture_.update(tmp);
 				break;
 
-		case ftl::rgbd::kChanFlow:
-		case ftl::rgbd::kChanConfidence:
-		case ftl::rgbd::kChanNormals:
-			case ftl::rgbd::kChanRight:
+		case Channel::Flow:
+		case Channel::Confidence:
+		case Channel::Normals:
+		case Channel::Right:
 				if (depth_.rows == 0 || depth_.type() != CV_8UC3) { break; }
 				texture_.update(depth_);
 				break;
diff --git a/applications/gui/src/camera.hpp b/applications/gui/src/camera.hpp
index f412d9c43d1809374566b1ba24c427ecda792695..605560cc0cae859678e25dbf2070d777a72e9112 100644
--- a/applications/gui/src/camera.hpp
+++ b/applications/gui/src/camera.hpp
@@ -32,11 +32,11 @@ class Camera {
 	void showPoseWindow();
 	void showSettings();
 
-	void setChannel(ftl::rgbd::channel_t c);
+	void setChannel(ftl::rgbd::Channel c);
 
 	void togglePause();
 	void isPaused();
-	const std::vector<ftl::rgbd::channel_t> &availableChannels();
+	const ftl::rgbd::Channels &availableChannels();
 
 	const GLTexture &captureFrame();
 
@@ -62,8 +62,8 @@ class Camera {
 	float lerpSpeed_;
 	bool sdepth_;
 	bool pause_;
-	ftl::rgbd::channel_t channel_;
-	std::vector<ftl::rgbd::channel_t> channels_;
+	ftl::rgbd::Channel channel_;
+	ftl::rgbd::Channels channels_;
 	cv::Mat rgb_;
 	cv::Mat depth_;
 	MUTEX mutex_;
diff --git a/applications/gui/src/media_panel.cpp b/applications/gui/src/media_panel.cpp
index 2ee06a69d09690e497bb8f88283a947b466aae46..cb44400bb1c850669332376e0134f138b9c460f3 100644
--- a/applications/gui/src/media_panel.cpp
+++ b/applications/gui/src/media_panel.cpp
@@ -12,6 +12,7 @@
 #endif
 
 using ftl::gui::MediaPanel;
+using ftl::rgbd::Channel;
 
 MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""), screen_(screen) {
 	using namespace nanogui;
@@ -115,7 +116,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanLeft);
+            cam->setChannel(Channel::Left);
         }
     });
 
@@ -124,7 +125,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     right_button_->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanRight);
+            cam->setChannel(Channel::Right);
         }
     });
 
@@ -133,7 +134,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     depth_button_->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanDepth);
+            cam->setChannel(Channel::Depth);
         }
     });
 
@@ -150,7 +151,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanDeviation);
+            cam->setChannel(Channel::Deviation);
         }
     });
 
@@ -159,7 +160,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanNormals);
+            cam->setChannel(Channel::Normals);
         }
     });
 
@@ -168,7 +169,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanFlow);
+            cam->setChannel(Channel::Flow);
         }
     });
 
@@ -177,7 +178,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanConfidence);
+            cam->setChannel(Channel::Confidence);
         }
     });
 
@@ -186,7 +187,7 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""),
     button->setCallback([this]() {
         ftl::gui::Camera *cam = screen_->activeCamera();
         if (cam) {
-            cam->setChannel(ftl::rgbd::kChanEnergy);
+            cam->setChannel(Channel::Energy);
         }
     });
 
diff --git a/applications/reconstruct/include/ftl/depth_camera.hpp b/applications/reconstruct/include/ftl/depth_camera.hpp
index cff8ff71f8872a965b2f05071e96f26a4b0a604a..39e037abd90f64e6730577578e09a1f69998b43c 100644
--- a/applications/reconstruct/include/ftl/depth_camera.hpp
+++ b/applications/reconstruct/include/ftl/depth_camera.hpp
@@ -4,8 +4,8 @@
 
 //#include <cutil_inline.h>
 //#include <cutil_math.h>
-#include <vector_types.h>
-#include <cuda_runtime.h>
+//#include <vector_types.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 #include <ftl/cuda_common.hpp>
diff --git a/applications/reconstruct/include/ftl/depth_camera_params.hpp b/applications/reconstruct/include/ftl/depth_camera_params.hpp
index 4864fccbdc9fa52647687e885f955a12132b0c04..c1c3b8e615577e2d4006ad15cfa975a27c5797fe 100644
--- a/applications/reconstruct/include/ftl/depth_camera_params.hpp
+++ b/applications/reconstruct/include/ftl/depth_camera_params.hpp
@@ -4,12 +4,13 @@
 
 //#include <cutil_inline.h>
 //#include <cutil_math.h>
-#include <vector_types.h>
-#include <cuda_runtime.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 #include <ftl/rgbd/camera.hpp>
 
+//#include <vector_types.h>
+
 struct __align__(16) DepthCameraParams {
 	float fx;
 	float fy;
diff --git a/applications/reconstruct/include/ftl/voxel_hash_params.hpp b/applications/reconstruct/include/ftl/voxel_hash_params.hpp
index 5e13ec21c259eec02d9a2f49b25ad3a98c06d08c..ac5fcaa726febaff0b56426b6d481d48bae3e421 100644
--- a/applications/reconstruct/include/ftl/voxel_hash_params.hpp
+++ b/applications/reconstruct/include/ftl/voxel_hash_params.hpp
@@ -4,8 +4,8 @@
 
 //#include <cutil_inline.h>
 //#include <cutil_math.h>
-#include <vector_types.h>
-#include <cuda_runtime.h>
+//#include <vector_types.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 
diff --git a/applications/reconstruct/include/ftl/voxel_scene.hpp b/applications/reconstruct/include/ftl/voxel_scene.hpp
index b1ee6f3bc1388a0c57398fc63971b7ccb163235a..4ea2d5eb3d98b0a3baac018f2c9ace9b5ad7a6f0 100644
--- a/applications/reconstruct/include/ftl/voxel_scene.hpp
+++ b/applications/reconstruct/include/ftl/voxel_scene.hpp
@@ -2,7 +2,7 @@
 
 #pragma once
 
-#include <cuda_runtime.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_common.hpp>
 #include <ftl/rgbd/source.hpp>
diff --git a/applications/reconstruct/src/dibr.cu b/applications/reconstruct/src/dibr.cu
index a7ba0e9df91637c687eda13d1048f323f72a30f4..fade3634314698772c46b126218765862d1adbaf 100644
--- a/applications/reconstruct/src/dibr.cu
+++ b/applications/reconstruct/src/dibr.cu
@@ -1,6 +1,6 @@
 #include "splat_render_cuda.hpp"
 #include "depth_camera_cuda.hpp"
-#include <cuda_runtime.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 
diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp
index 01745d2dd2e6dcaf902fa4260f781a3b7fb3dea0..f381d9de555d7e534703e02b809f2a7568394b47 100644
--- a/applications/reconstruct/src/main.cpp
+++ b/applications/reconstruct/src/main.cpp
@@ -37,6 +37,7 @@ using std::string;
 using std::vector;
 using ftl::rgbd::Source;
 using ftl::config::json_t;
+using ftl::rgbd::Channel;
 
 using json = nlohmann::json;
 using std::this_thread::sleep_for;
@@ -104,7 +105,7 @@ static void run(ftl::Configurable *root) {
 
 	for (size_t i=0; i<sources.size(); i++) {
 		Source *in = sources[i];
-		in->setChannel(ftl::rgbd::kChanDepth);
+		in->setChannel(Channel::Depth);
 		//stream->add(in);
 		scene->addSource(in);
 		group.addSource(in);
diff --git a/applications/reconstruct/src/ray_cast_sdf.cu b/applications/reconstruct/src/ray_cast_sdf.cu
index a43b608429b1fad1ac160b188c9be6b084274154..10fd3e0b7b84ca694432abc7dc68fc513ad483eb 100644
--- a/applications/reconstruct/src/ray_cast_sdf.cu
+++ b/applications/reconstruct/src/ray_cast_sdf.cu
@@ -1,5 +1,5 @@
 
-#include <cuda_runtime.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 
diff --git a/applications/reconstruct/src/scene_rep_hash_sdf.cu b/applications/reconstruct/src/scene_rep_hash_sdf.cu
index 247247b6cc5279186f9f9bdc81bbe627ab0621ea..4750d3e7ed4f7aeb68875e0b5050d76efed5b715 100644
--- a/applications/reconstruct/src/scene_rep_hash_sdf.cu
+++ b/applications/reconstruct/src/scene_rep_hash_sdf.cu
@@ -2,8 +2,8 @@
 
 //#include <cutil_inline.h>
 //#include <cutil_math.h>
-#include <vector_types.h>
-#include <cuda_runtime.h>
+//#include <vector_types.h>
+//#include <cuda_runtime.h>
 
 #include <ftl/cuda_matrix_util.hpp>
 
diff --git a/applications/reconstruct/src/splat_render.cpp b/applications/reconstruct/src/splat_render.cpp
index cc52bb7bf33d8688a9fc1da9f3b0d07474aff811..21e1b1db3952422e82be757fec56d3c75de0b4c8 100644
--- a/applications/reconstruct/src/splat_render.cpp
+++ b/applications/reconstruct/src/splat_render.cpp
@@ -4,6 +4,7 @@
 #include "depth_camera_cuda.hpp"
 
 using ftl::render::Splatter;
+using ftl::rgbd::Channel;
 
 Splatter::Splatter(ftl::voxhash::SceneRep *scene) : scene_(scene) {
 
@@ -85,7 +86,7 @@ void Splatter::render(int64_t ts, ftl::rgbd::Source *src, cudaStream_t stream) {
 		// Step 2: For each point, use a warp to do MLS and up sample
 		//ftl::cuda::mls_render_depth(depth1_, depth3_, params, scene_->cameraCount(), stream);
 
-		if (src->getChannel() == ftl::rgbd::kChanDepth) {
+		if (src->getChannel() == Channel::Depth) {
 			//ftl::cuda::int_to_float(depth1_, depth2_, 1.0f / 1000.0f, stream);
 			if (src->value("splatting",  false)) {
 				//ftl::cuda::splat_points(depth1_, colour1_, normal1_, depth2_, colour2_, params, stream);
@@ -95,7 +96,7 @@ void Splatter::render(int64_t ts, ftl::rgbd::Source *src, cudaStream_t stream) {
 				ftl::cuda::int_to_float(depth1_, depth2_, 1.0f / 1000.0f, stream);
 				src->writeFrames(ts, colour1_, depth2_, stream);
 			}
-		} else if (src->getChannel() == ftl::rgbd::kChanEnergy) {
+		} else if (src->getChannel() == Channel::Energy) {
 			//ftl::cuda::int_to_float(depth1_, depth2_, 1.0f / 1000.0f, stream);
 			//if (src->value("splatting",  false)) {
 				//ftl::cuda::splat_points(depth1_, colour1_, normal1_, depth2_, colour2_, params, stream);
@@ -105,7 +106,7 @@ void Splatter::render(int64_t ts, ftl::rgbd::Source *src, cudaStream_t stream) {
 				//ftl::cuda::int_to_float(depth1_, depth2_, 1.0f / 1000.0f, stream);
 			//	src->writeFrames(colour1_, depth2_, stream);
 			//}
-		} else if (src->getChannel() == ftl::rgbd::kChanRight) {
+		} else if (src->getChannel() == Channel::Right) {
 			// Adjust pose to right eye position
 			Eigen::Affine3f transform(Eigen::Translation3f(camera.baseline,0.0f,0.0f));
 			Eigen::Matrix4f matrix =  src->getPose().cast<float>() * transform.matrix();
diff --git a/applications/reconstruct/src/voxel_scene.cpp b/applications/reconstruct/src/voxel_scene.cpp
index 63844fcc8c5dc6cf188166e5d17dbdaadd4cb8ae..09067b1f2334e0190e27022b64d374e31532f8c2 100644
--- a/applications/reconstruct/src/voxel_scene.cpp
+++ b/applications/reconstruct/src/voxel_scene.cpp
@@ -7,6 +7,7 @@
 
 using namespace ftl::voxhash;
 using ftl::rgbd::Source;
+using ftl::rgbd::Channel;
 using ftl::Configurable;
 using cv::Mat;
 using std::vector;
@@ -95,7 +96,7 @@ void SceneRep::addSource(ftl::rgbd::Source *src) {
 	auto &cam = cameras_.emplace_back();
 	cam.source = src;
 	cam.params.m_imageWidth = 0;
-	src->setChannel(ftl::rgbd::kChanDepth);
+	src->setChannel(Channel::Depth);
 }
 
 extern "C" void updateCUDACameraConstant(ftl::voxhash::DepthCameraCUDA *data, int count);
@@ -230,8 +231,10 @@ int SceneRep::upload(ftl::rgbd::FrameSet &fs) {
 
 	for (size_t i=0; i<cameras_.size(); ++i) {
 		auto &cam = cameras_[i];
-		auto &chan1 = fs.frames[i].getChannel<cv::Mat>(ftl::rgbd::kChanColour);
-		auto &chan2 = fs.frames[i].getChannel<cv::Mat>(fs.sources[i]->getChannel());
+		auto &chan1 = fs.frames[i].get<cv::Mat>(Channel::Colour);
+		auto &chan2 = fs.frames[i].get<cv::Mat>(fs.sources[i]->getChannel());
+
+		auto test = fs.frames[i].createTexture<uchar4>(Channel::Flow, ftl::rgbd::Format<uchar4>(100,100));
 
 		// Get the RGB-Depth frame from input
 		Source *input = cam.source;
diff --git a/components/codecs/include/ftl/codecs/encoder.hpp b/components/codecs/include/ftl/codecs/encoder.hpp
index 4adeb4b0d625661306321073fad9f84383ed2a42..560810b84060b3b062b426614da40836634fdee5 100644
--- a/components/codecs/include/ftl/codecs/encoder.hpp
+++ b/components/codecs/include/ftl/codecs/encoder.hpp
@@ -1,6 +1,7 @@
 #ifndef _FTL_CODECS_ENCODER_HPP_
 #define _FTL_CODECS_ENCODER_HPP_
 
+#include <ftl/cuda_util.hpp>
 #include <opencv2/opencv.hpp>
 #include <opencv2/core/cuda.hpp>
 
diff --git a/components/codecs/src/nvpipe_decoder.cpp b/components/codecs/src/nvpipe_decoder.cpp
index cbeced55e0bd07c1347523c5c682767a769055c0..0dda5884cc7bf156e7cb134795e6f0ff2c180130 100644
--- a/components/codecs/src/nvpipe_decoder.cpp
+++ b/components/codecs/src/nvpipe_decoder.cpp
@@ -2,7 +2,8 @@
 
 #include <loguru.hpp>
 
-#include <cuda_runtime.h>
+#include <ftl/cuda_util.hpp>
+//#include <cuda_runtime.h>
 
 using ftl::codecs::NvPipeDecoder;
 
diff --git a/components/codecs/src/nvpipe_encoder.cpp b/components/codecs/src/nvpipe_encoder.cpp
index 1060f0f2a581966cb7fe1b537999d3ab914f506b..cbae706ef8d5729615d4084ca8c024fc69333ea2 100644
--- a/components/codecs/src/nvpipe_encoder.cpp
+++ b/components/codecs/src/nvpipe_encoder.cpp
@@ -2,7 +2,7 @@
 #include <loguru.hpp>
 #include <ftl/timer.hpp>
 #include <ftl/codecs/bitrates.hpp>
-#include <cuda_runtime.h>
+#include <ftl/cuda_util.hpp>
 
 using ftl::codecs::NvPipeEncoder;
 using ftl::codecs::bitrate_t;
diff --git a/components/common/cpp/include/ftl/cuda_common.hpp b/components/common/cpp/include/ftl/cuda_common.hpp
index 3f004d0c8ffefaf692b84106dea3810e223d70f3..09a1dd062ad62bd3e8c0c7384a201a8565573517 100644
--- a/components/common/cpp/include/ftl/cuda_common.hpp
+++ b/components/common/cpp/include/ftl/cuda_common.hpp
@@ -2,12 +2,19 @@
 #define _FTL_CUDA_COMMON_HPP_
 
 #include <ftl/config.h>
+#include <ftl/traits.hpp>
 
 #if defined HAVE_CUDA
 
+#include <ftl/cuda_util.hpp>
 #include <opencv2/core/cuda.hpp>
 #include <opencv2/core/cuda/common.hpp>
 
+#ifndef __CUDACC__
+#include <loguru.hpp>
+#include <exception>
+#endif
+
 /* Grid stride loop macros */
 #define STRIDE_Y(I,N) int I = blockIdx.y * blockDim.y + threadIdx.y; I < N; I += blockDim.y * gridDim.y
 #define STRIDE_X(I,N) int I = blockIdx.x * blockDim.x + threadIdx.x; I < N; I += blockDim.x * gridDim.x
@@ -15,69 +22,144 @@
 namespace ftl {
 namespace cuda {
 
-/*template <typename T>
-class HisteresisTexture {
+/**
+ * Represent a CUDA texture object. Instances of this class can be used on both
+ * host and device. A texture object base cannot be constructed directly, it
+ * must be constructed via a template TextureObject class.
+ */
+class TextureObjectBase {
 	public:
-	HisteresisTexture();
-	~HisteresisTexture();
+	__host__ __device__ TextureObjectBase()
+			: texobj_(0), pitch_(0), pitch2_(0), width_(0), height_(0),
+			  ptr_(nullptr), needsfree_(false), needsdestroy_(false),
+			  cvType_(-1) {};
+	~TextureObjectBase();
+
+	// Remove ability to copy object directly, instead must use
+	// templated derivative TextureObject.
+	TextureObjectBase(const TextureObjectBase &)=delete;
+	TextureObjectBase &operator=(const TextureObjectBase &)=delete;
+
+	TextureObjectBase(TextureObjectBase &&);
+	TextureObjectBase &operator=(TextureObjectBase &&);
+
+	inline size_t pitch() const { return pitch_; }
+	inline size_t pixelPitch() const { return pitch2_; }
+	inline uchar *devicePtr() const { return ptr_; };
+	__host__ __device__ inline uchar *devicePtr(int v) const { return &ptr_[v*pitch_]; }
+	__host__ __device__ inline int width() const { return width_; }
+	__host__ __device__ inline int height() const { return height_; }
+	__host__ __device__ inline cudaTextureObject_t cudaTexture() const { return texobj_; }
+
+	void upload(const cv::Mat &, cudaStream_t stream=0);
+	void download(cv::Mat &, cudaStream_t stream=0) const;
 	
-	HisteresisTexture<T> &operator=(TextureObject<T> &t);
-};*/
+	__host__ void free();
 
+	inline int cvType() const { return cvType_; }
+	
+	protected:
+	cudaTextureObject_t texobj_;
+	size_t pitch_;
+	size_t pitch2_; 		// in T units
+	int width_;
+	int height_;
+	uchar *ptr_;			// Device memory pointer
+	bool needsfree_;		// We manage memory, so free it
+	bool needsdestroy_;		// The texture object needs to be destroyed
+	int cvType_;				// Used to validate casting
+};
+
+/**
+ * Create and manage CUDA texture objects with a particular pixel data type.
+ * Note: it is not possible to create texture objects for certain types,
+ * specificially for 3 channel types.
+ */
 template <typename T>
-class TextureObject {
+class TextureObject : public TextureObjectBase {
 	public:
-	__host__ __device__ TextureObject()
-			: texobj_(0), pitch_(0), pitch2_(0), width_(0), height_(0), ptr_(nullptr), needsfree_(false) {};
-	TextureObject(const cv::cuda::PtrStepSz<T> &d);
+	typedef T type;
+
+	static_assert((16u % sizeof(T)) == 0, "Channel format must be aligned with 16 bytes");
+
+	__host__ __device__ TextureObject() : TextureObjectBase() {};
+	explicit TextureObject(const cv::cuda::GpuMat &d);
+	explicit TextureObject(const cv::cuda::PtrStepSz<T> &d);
 	TextureObject(T *ptr, int pitch, int width, int height);
 	TextureObject(size_t width, size_t height);
 	TextureObject(const TextureObject<T> &t);
 	__host__ __device__ TextureObject(TextureObject<T> &&);
 	~TextureObject();
 
-	__host__ TextureObject<T> &operator=(const TextureObject<T> &);
+	TextureObject<T> &operator=(const TextureObject<T> &);
 	__host__ __device__ TextureObject<T> &operator=(TextureObject<T> &&);
-	
-	size_t pitch() const { return pitch_; }
-	size_t pixelPitch() const { return pitch2_; }
-	T *devicePtr() const { return ptr_; };
-	__host__ __device__ T *devicePtr(int v) const { return &ptr_[v*pitch2_]; }
-	__host__ __device__ int width() const { return width_; }
-	__host__ __device__ int height() const { return height_; }
-	__host__ __device__ cudaTextureObject_t cudaTexture() const { return texobj_; }
+
+	operator cv::cuda::GpuMat();
+
+	__host__ __device__ T *devicePtr() const { return (T*)(ptr_); };
+	__host__ __device__ T *devicePtr(int v) const { return &(T*)(ptr_)[v*pitch2_]; }
 
 	#ifdef __CUDACC__
 	__device__ inline T tex2D(int u, int v) const { return ::tex2D<T>(texobj_, u, v); }
 	__device__ inline T tex2D(float u, float v) const { return ::tex2D<T>(texobj_, u, v); }
 	#endif
 
-	__host__ __device__ inline const T &operator()(int u, int v) const { return ptr_[u+v*pitch2_]; }
-	__host__ __device__ inline T &operator()(int u, int v) { return ptr_[u+v*pitch2_]; }
+	__host__ __device__ inline const T &operator()(int u, int v) const { return reinterpret_cast<T*>(ptr_)[u+v*pitch2_]; }
+	__host__ __device__ inline T &operator()(int u, int v) { return reinterpret_cast<T*>(ptr_)[u+v*pitch2_]; }
 
-	void upload(const cv::Mat &, cudaStream_t stream=0);
-	void download(cv::Mat &, cudaStream_t stream=0) const;
-	
-	__host__ void free() {
-		if (needsfree_) {
-			if (texobj_ != 0) cudaSafeCall( cudaDestroyTextureObject (texobj_) );
-			if (ptr_) cudaFree(ptr_);
-			ptr_ = nullptr;
-			texobj_ = 0;
-		}
-	}
-	
-	private:
-	cudaTextureObject_t texobj_;
-	size_t pitch_;
-	size_t pitch2_; // in T units
-	int width_;
-	int height_;
-	T *ptr_;
-	bool needsfree_;
-	//bool needsdestroy_;
+	/**
+	 * Cast a base texture object to this type of texture object. If the
+	 * underlying pixel types do not match then a bad_cast exception is thrown.
+	 */
+	static TextureObject<T> &cast(TextureObjectBase &);
 };
 
+#ifndef __CUDACC__
+template <typename T>
+TextureObject<T> &TextureObject<T>::cast(TextureObjectBase &b) {
+	if (b.cvType() != ftl::traits::OpenCVType<T>::value) {
+		LOG(ERROR) << "Bad cast of texture object";
+		throw std::bad_cast();
+	}
+	return reinterpret_cast<TextureObject<T>&>(b);
+}
+
+/**
+ * Create a 2D array texture from an OpenCV GpuMat object.
+ */
+template <typename T>
+TextureObject<T>::TextureObject(const cv::cuda::GpuMat &d) {
+	// GpuMat must have correct data type
+	CHECK(d.type() == ftl::traits::OpenCVType<T>::value);
+
+	cudaResourceDesc resDesc;
+	memset(&resDesc, 0, sizeof(resDesc));
+	resDesc.resType = cudaResourceTypePitch2D;
+	resDesc.res.pitch2D.devPtr = d.data;
+	resDesc.res.pitch2D.pitchInBytes = d.step;
+	resDesc.res.pitch2D.desc = cudaCreateChannelDesc<T>();
+	resDesc.res.pitch2D.width = d.cols;
+	resDesc.res.pitch2D.height = d.rows;
+
+	cudaTextureDesc texDesc;
+	memset(&texDesc, 0, sizeof(texDesc));
+	texDesc.readMode = cudaReadModeElementType;
+
+	cudaTextureObject_t tex = 0;
+	cudaSafeCall(cudaCreateTextureObject(&tex, &resDesc, &texDesc, NULL));
+	texobj_ = tex;
+	pitch_ = d.step;
+	pitch2_ = pitch_ / sizeof(T);
+	ptr_ = d.data;
+	width_ = d.cols;
+	height_ = d.rows;
+	needsfree_ = false;
+	cvType_ = ftl::traits::OpenCVType<T>::value;
+	//needsdestroy_ = true;
+}
+
+#endif  // __CUDACC__
+
 /**
  * Create a 2D array texture from an OpenCV GpuMat object.
  */
@@ -105,6 +187,7 @@ TextureObject<T>::TextureObject(const cv::cuda::PtrStepSz<T> &d) {
 	width_ = d.cols;
 	height_ = d.rows;
 	needsfree_ = false;
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	//needsdestroy_ = true;
 }
 
@@ -136,6 +219,7 @@ TextureObject<T>::TextureObject(T *ptr, int pitch, int width, int height) {
 	width_ = width;
 	height_ = height;
 	needsfree_ = false;
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	//needsdestroy_ = true;
 }
 
@@ -166,6 +250,7 @@ TextureObject<T>::TextureObject(size_t width, size_t height) {
 	height_ = (int)height;
 	needsfree_ = true;
 	pitch2_ = pitch_ / sizeof(T);
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	//needsdestroy_ = true;
 }
 
@@ -177,6 +262,7 @@ TextureObject<T>::TextureObject(const TextureObject<T> &p) {
 	height_ = p.height_;
 	pitch_ = p.pitch_;
 	pitch2_ = pitch_ / sizeof(T);
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	needsfree_ = false;
 }
 
@@ -192,6 +278,7 @@ TextureObject<T>::TextureObject(TextureObject<T> &&p) {
 	p.texobj_ = 0;
 	p.needsfree_ = false;
 	p.ptr_ = nullptr;
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 }
 
 template <typename T>
@@ -202,6 +289,7 @@ TextureObject<T> &TextureObject<T>::operator=(const TextureObject<T> &p) {
 	height_ = p.height_;
 	pitch_ = p.pitch_;
 	pitch2_ = pitch_ / sizeof(T);
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	needsfree_ = false;
 	return *this;
 }
@@ -218,6 +306,7 @@ TextureObject<T> &TextureObject<T>::operator=(TextureObject<T> &&p) {
 	p.texobj_ = 0;
 	p.needsfree_ = false;
 	p.ptr_ = nullptr;
+	cvType_ = ftl::traits::OpenCVType<T>::value;
 	return *this;
 }
 
@@ -228,7 +317,7 @@ TextureObject<T>::~TextureObject() {
 	free();
 }
 
-template <>
+/*template <>
 void TextureObject<uchar4>::upload(const cv::Mat &m, cudaStream_t stream);
 
 template <>
@@ -257,7 +346,7 @@ template <>
 void TextureObject<float4>::download(cv::Mat &m, cudaStream_t stream) const;
 
 template <>
-void TextureObject<uchar>::download(cv::Mat &m, cudaStream_t stream) const;
+void TextureObject<uchar>::download(cv::Mat &m, cudaStream_t stream) const;*/
 
 }
 }
diff --git a/components/common/cpp/include/ftl/cuda_operators.hpp b/components/common/cpp/include/ftl/cuda_operators.hpp
index ae85cfbd785fb72f79225ae28278bf4862b680db..5fc84fbcb158bc599b8bca55e38035757a857648 100644
--- a/components/common/cpp/include/ftl/cuda_operators.hpp
+++ b/components/common/cpp/include/ftl/cuda_operators.hpp
@@ -19,7 +19,8 @@
 #ifndef _FTL_CUDA_OPERATORS_HPP_
 #define _FTL_CUDA_OPERATORS_HPP_
 
-#include <cuda_runtime.h>
+//#include <cuda_runtime.h>
+#include <ftl/cuda_util.hpp>
 
 
 ////////////////////////////////////////////////////////////////////////////////
diff --git a/components/common/cpp/include/ftl/cuda_util.hpp b/components/common/cpp/include/ftl/cuda_util.hpp
index bf018f07919fe52c71a1104a6bf029ce52f17b8e..e55c1430c1c013780e4b5d9fc0381492da281e49 100644
--- a/components/common/cpp/include/ftl/cuda_util.hpp
+++ b/components/common/cpp/include/ftl/cuda_util.hpp
@@ -6,7 +6,12 @@
 #undef max
 #undef min
 
+#ifdef CPPCHECK
+#define __align__(A)
+#endif
+
 #include <cuda_runtime.h>
+#include <vector_types.h>
 #include <ftl/cuda_operators.hpp>
 
 // Enable run time assertion checking in kernel code
diff --git a/components/common/cpp/include/ftl/exception.hpp b/components/common/cpp/include/ftl/exception.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..6719158bba5f5f53abfcdeb0fb39a5b5dda0d5f2
--- /dev/null
+++ b/components/common/cpp/include/ftl/exception.hpp
@@ -0,0 +1,19 @@
+#ifndef _FTL_EXCEPTION_HPP_
+#define _FTL_EXCEPTION_HPP_
+
+namespace ftl {
+class exception : public std::exception
+{
+	public:
+	explicit exception(const char *msg) : msg_(msg) {};
+
+	const char * what () const throw () {
+    	return msg_;
+    }
+
+	private:
+	const char *msg_;
+};
+}
+
+#endif  // _FTL_EXCEPTION_HPP_
diff --git a/components/common/cpp/include/ftl/traits.hpp b/components/common/cpp/include/ftl/traits.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..6ac54e8e66f6a12aa13e39e1228f5cf17ca69312
--- /dev/null
+++ b/components/common/cpp/include/ftl/traits.hpp
@@ -0,0 +1,44 @@
+#ifndef _FTL_TRAITS_HPP_
+#define _FTL_TRAITS_HPP_
+
+#include <opencv2/core.hpp>
+#include <ftl/cuda_util.hpp>
+
+namespace ftl {
+namespace traits {
+
+template <typename T>
+struct AlwaysFalse : std::false_type {};
+
+template <typename T> struct OpenCVType {
+	static_assert(AlwaysFalse<T>::value, "Not a valid format type");
+};
+template <> struct OpenCVType<uchar> { static const int value = CV_8UC1; };
+template <> struct OpenCVType<uchar2> { static const int value = CV_8UC2; };
+template <> struct OpenCVType<uchar3> { static const int value = CV_8UC3; };
+template <> struct OpenCVType<uchar4> { static const int value = CV_8UC4; };
+template <> struct OpenCVType<char> { static const int value = CV_8SC1; };
+template <> struct OpenCVType<char2> { static const int value = CV_8SC2; };
+template <> struct OpenCVType<char3> { static const int value = CV_8SC3; };
+template <> struct OpenCVType<char4> { static const int value = CV_8SC4; };
+template <> struct OpenCVType<ushort> { static const int value = CV_16UC1; };
+template <> struct OpenCVType<ushort2> { static const int value = CV_16UC2; };
+template <> struct OpenCVType<ushort3> { static const int value = CV_16UC3; };
+template <> struct OpenCVType<ushort4> { static const int value = CV_16UC4; };
+template <> struct OpenCVType<short> { static const int value = CV_16SC1; };
+template <> struct OpenCVType<short2> { static const int value = CV_16SC2; };
+template <> struct OpenCVType<short3> { static const int value = CV_16SC3; };
+template <> struct OpenCVType<short4> { static const int value = CV_16SC4; };
+template <> struct OpenCVType<int> { static const int value = CV_32SC1; };
+template <> struct OpenCVType<int2> { static const int value = CV_32SC2; };
+template <> struct OpenCVType<int3> { static const int value = CV_32SC3; };
+template <> struct OpenCVType<int4> { static const int value = CV_32SC4; };
+template <> struct OpenCVType<float> { static const int value = CV_32FC1; };
+template <> struct OpenCVType<float2> { static const int value = CV_32FC2; };
+template <> struct OpenCVType<float3> { static const int value = CV_32FC3; };
+template <> struct OpenCVType<float4> { static const int value = CV_32FC4; };
+
+}
+}
+
+#endif  // _FTL_TRAITS_HPP_
diff --git a/components/common/cpp/src/cuda_common.cpp b/components/common/cpp/src/cuda_common.cpp
index 571d6816b63413163471ef9006ae1d28031511fd..15fa9c94963bb073647f609176f3f022a084d4a0 100644
--- a/components/common/cpp/src/cuda_common.cpp
+++ b/components/common/cpp/src/cuda_common.cpp
@@ -1,8 +1,72 @@
 #include <ftl/cuda_common.hpp>
 
-using ftl::cuda::TextureObject;
+using ftl::cuda::TextureObjectBase;
 
-template <>
+TextureObjectBase::~TextureObjectBase() {
+	free();
+}
+
+TextureObjectBase::TextureObjectBase(TextureObjectBase &&o) {
+	needsfree_ = o.needsfree_;
+	needsdestroy_ = o.needsdestroy_;
+	ptr_ = o.ptr_;
+	texobj_ = o.texobj_;
+	cvType_ = o.cvType_;
+	width_ = o.width_;
+	height_ = o.height_;
+	pitch_ = o.pitch_;
+	pitch2_ = o.pitch2_;
+
+	o.ptr_ = nullptr;
+	o.needsfree_ = false;
+	o.texobj_ = 0;
+	o.needsdestroy_ = false;
+}
+
+TextureObjectBase &TextureObjectBase::operator=(TextureObjectBase &&o) {
+	free();
+
+	needsfree_ = o.needsfree_;
+	needsdestroy_ = o.needsdestroy_;
+	ptr_ = o.ptr_;
+	texobj_ = o.texobj_;
+	cvType_ = o.cvType_;
+	width_ = o.width_;
+	height_ = o.height_;
+	pitch_ = o.pitch_;
+	pitch2_ = o.pitch2_;
+
+	o.ptr_ = nullptr;
+	o.needsfree_ = false;
+	o.texobj_ = 0;
+	o.needsdestroy_ = false;
+	return *this;
+}
+
+void TextureObjectBase::free() {
+	if (needsfree_) {
+		if (texobj_ != 0) cudaSafeCall( cudaDestroyTextureObject (texobj_) );
+		if (ptr_) cudaFree(ptr_);
+		ptr_ = nullptr;
+		texobj_ = 0;
+		cvType_ = -1;
+	} else if (needsdestroy_) {
+		if (texobj_ != 0) cudaSafeCall( cudaDestroyTextureObject (texobj_) );
+		texobj_ = 0;
+		cvType_ = -1;
+	}
+}
+
+void TextureObjectBase::upload(const cv::Mat &m, cudaStream_t stream) {
+    cudaSafeCall(cudaMemcpy2DAsync(devicePtr(), pitch(), m.data, m.step, m.cols * m.elemSize(), m.rows, cudaMemcpyHostToDevice, stream));
+}
+
+void TextureObjectBase::download(cv::Mat &m, cudaStream_t stream) const {
+	m.create(height(), width(), cvType_);
+	cudaSafeCall(cudaMemcpy2DAsync(m.data, m.step, devicePtr(), pitch(), m.cols * m.elemSize(), m.rows, cudaMemcpyDeviceToHost, stream));
+}
+
+/*template <>
 void TextureObject<uchar4>::upload(const cv::Mat &m, cudaStream_t stream) {
     cudaSafeCall(cudaMemcpy2DAsync(devicePtr(), pitch(), m.data, m.step, m.cols * sizeof(uchar4), m.rows, cudaMemcpyHostToDevice, stream));
 }
@@ -56,4 +120,4 @@ template <>
 void TextureObject<uchar>::download(cv::Mat &m, cudaStream_t stream) const {
 	m.create(height(), width(), CV_8UC1);
 	cudaSafeCall(cudaMemcpy2DAsync(m.data, m.step, devicePtr(), pitch(), m.cols * sizeof(uchar), m.rows, cudaMemcpyDeviceToHost, stream));
-}
+}*/
diff --git a/components/rgbd-sources/CMakeLists.txt b/components/rgbd-sources/CMakeLists.txt
index ff7d290981c1a84c5ee211219ae0651f85c58c77..3ac2e2de5f173a12bd7107d8d40b5d2eca3b4b5d 100644
--- a/components/rgbd-sources/CMakeLists.txt
+++ b/components/rgbd-sources/CMakeLists.txt
@@ -37,6 +37,7 @@ endif (LIBSGM_FOUND)
 if (CUDA_FOUND)
 	list(APPEND RGBDSRC
 		src/algorithms/disp2depth.cu
+		src/algorithms/offilter.cu
 #		"src/algorithms/opencv_cuda_bm.cpp"
 #		"src/algorithms/opencv_cuda_bp.cpp"
 #		"src/algorithms/rtcensus.cu"
diff --git a/components/rgbd-sources/include/ftl/offilter.hpp b/components/rgbd-sources/include/ftl/offilter.hpp
index 4c4fbbb9837ef39e80f9aad68c62ae5d82d4671e..6aece39aab241dfc7605dfb208d7d30ba6135509 100644
--- a/components/rgbd-sources/include/ftl/offilter.hpp
+++ b/components/rgbd-sources/include/ftl/offilter.hpp
@@ -1,8 +1,10 @@
 #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>
@@ -12,23 +14,15 @@ namespace rgbd {
 
 class OFDisparityFilter {
 public:
-	OFDisparityFilter() : n_max_(0), threshold_(0.0), size_(0, 0) {} // TODO: invalid state
+	OFDisparityFilter() : n_max_(0), threshold_(0.0) {}
 	OFDisparityFilter(cv::Size size, int n_frames, float threshold);
-	void filter(cv::Mat &disp, const cv::Mat &rgb);
+	void filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream);
 
 private:
-	int n_;
 	int n_max_;
 	float threshold_;
-	cv::Size size_;
 
-	cv::Mat disp_;
-	cv::Mat gray_;
-
-	cv::Mat flowxy_;
-	cv::Mat flowxy_up_;
-
-	cv::Ptr<cv::cuda::NvidiaOpticalFlow_1_0> nvof_;
+	cv::cuda::GpuMat disp_old_;
 };
 
 }
diff --git a/components/rgbd-sources/include/ftl/rgbd/channels.hpp b/components/rgbd-sources/include/ftl/rgbd/channels.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..591e0e312b0c5a161dc40ed0d4966852d8781971
--- /dev/null
+++ b/components/rgbd-sources/include/ftl/rgbd/channels.hpp
@@ -0,0 +1,92 @@
+#ifndef _FTL_RGBD_CHANNELS_HPP_
+#define _FTL_RGBD_CHANNELS_HPP_
+
+#include <bitset>
+#include <msgpack.hpp>
+
+namespace ftl {
+namespace rgbd {
+
+enum struct Channel : int {
+    None = -1,
+    Colour = 0,
+    Left = 0,
+    Depth = 1,
+    Right,
+    Disparity,
+    Deviation,
+    Normals,
+    Confidence,
+    Flow,
+    Energy,
+    LeftGray,
+    RightGray,
+    Overlay1
+};
+
+class Channels {
+    public:
+    inline Channels() { mask = 0; }
+    inline explicit Channels(unsigned int m) { mask = m; }
+    inline explicit Channels(Channel c) { mask = (c == Channel::None) ? 0 : 0x1 << static_cast<unsigned int>(c); }
+    inline Channels &operator=(Channel c) { mask = (c == Channel::None) ? 0 : 0x1 << static_cast<unsigned int>(c); return *this; }
+    inline Channels operator|(Channel c) const { return (c == Channel::None) ? Channels(mask) : Channels(mask | (0x1 << static_cast<unsigned int>(c))); }
+    inline Channels operator+(Channel c) const { return (c == Channel::None) ? Channels(mask) : Channels(mask | (0x1 << static_cast<unsigned int>(c))); }
+    inline Channels &operator|=(Channel c) { mask |= (c == Channel::None) ? 0 : (0x1 << static_cast<unsigned int>(c)); return *this; }
+    inline Channels &operator+=(Channel c) { mask |= (c == Channel::None) ? 0 : (0x1 << static_cast<unsigned int>(c)); return *this; }
+    inline Channels &operator-=(Channel c) { mask &= ~((c == Channel::None) ? 0 : (0x1 << static_cast<unsigned int>(c))); return *this; }
+    inline Channels &operator+=(unsigned int c) { mask |= (0x1 << c); return *this; }
+    inline Channels &operator-=(unsigned int c) { mask &= ~(0x1 << c); return *this; }
+
+    inline bool has(Channel c) const {
+        return (c == Channel::None) ? true : mask & (0x1 << static_cast<unsigned int>(c));
+    }
+
+    inline bool has(unsigned int c) const {
+        return mask & (0x1 << c);
+    }
+
+    inline operator unsigned int() { return mask; }
+    inline operator bool() { return mask > 0; }
+    inline operator Channel() {
+        if (mask == 0) return Channel::None;
+        int ix = 0;
+        int tmask = mask;
+        while (!(tmask & 0x1) && ++ix < 32) tmask >>= 1;
+        return static_cast<Channel>(ix);
+    }
+    
+    inline size_t count() { return std::bitset<32>(mask).count(); }
+    inline void clear() { mask = 0; }
+
+    static const size_t kMax = 32;
+
+    private:
+    unsigned int mask;
+};
+
+static const Channels kNoChannels;
+static const Channels kAllChannels(0xFFFFFFFFu);
+
+inline bool isFloatChannel(ftl::rgbd::Channel chan) {
+	switch (chan) {
+	case Channel::Depth		:
+	case Channel::Energy	: return true;
+	default					: return false;
+	}
+}
+
+}
+}
+
+MSGPACK_ADD_ENUM(ftl::rgbd::Channel);
+
+inline ftl::rgbd::Channels operator|(ftl::rgbd::Channel a, ftl::rgbd::Channel b) {
+    return ftl::rgbd::Channels(a) | b;
+}
+
+inline ftl::rgbd::Channels operator+(ftl::rgbd::Channel a, ftl::rgbd::Channel b) {
+    return ftl::rgbd::Channels(a) | b;
+}
+
+#endif  // _FTL_RGBD_CHANNELS_HPP_
diff --git a/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp b/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp
index 29edf722fe4a3eaac36c76f7c861797f8ff71a49..e98ff38aacd4cf0731ef96b67ecc85732d4c0c7f 100644
--- a/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp
@@ -2,6 +2,7 @@
 #define _FTL_RGBD_DETAIL_SOURCE_HPP_
 
 #include <Eigen/Eigen>
+#include <ftl/cuda_util.hpp>
 #include <opencv2/opencv.hpp>
 #include <ftl/rgbd/camera.hpp>
 #include <ftl/rgbd/frame.hpp>
@@ -55,7 +56,7 @@ class Source {
 	virtual bool isReady() { return false; };
 	virtual void setPose(const Eigen::Matrix4d &pose) { };
 
-	virtual Camera parameters(channel_t) { return params_; };
+	virtual Camera parameters(ftl::rgbd::Channel) { return params_; };
 
 	protected:
 	capability_t capabilities_;
diff --git a/components/rgbd-sources/include/ftl/rgbd/format.hpp b/components/rgbd-sources/include/ftl/rgbd/format.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..2e86aaf96a5f64d13065385ddee360fd80ca9f8c
--- /dev/null
+++ b/components/rgbd-sources/include/ftl/rgbd/format.hpp
@@ -0,0 +1,52 @@
+#ifndef _FTL_RGBD_FORMAT_HPP_
+#define _FTL_RGBD_FORMAT_HPP_
+
+#include <opencv2/core.hpp>
+#include <opencv2/core/cuda.hpp>
+#include <ftl/cuda_util.hpp>
+#include <ftl/codecs/bitrates.hpp>
+#include <ftl/traits.hpp>
+
+namespace ftl {
+namespace rgbd {
+
+struct FormatBase {
+	FormatBase(size_t w, size_t h, int t) : width(w), height(h), cvType(t) {}
+
+	size_t width;		// Width in pixels
+	size_t height;		// Height in pixels
+	int cvType;			// OpenCV Mat type
+
+	inline bool empty() const { return width == 0 || height == 0; }
+	inline cv::Size size() const { return cv::Size(width, height); }
+};
+
+template <typename T>
+struct Format : public ftl::rgbd::FormatBase {
+	Format() : FormatBase(0,0,0) {}
+
+	Format(size_t w, size_t h) : FormatBase(
+			w, h, ftl::traits::OpenCVType<T>::value) {}
+
+	explicit Format(ftl::codecs::definition_t d) : FormatBase(
+			ftl::codecs::getWidth(d),
+			ftl::codecs::getHeight(d),
+			ftl::traits::OpenCVType<T>::value) {}
+
+	explicit Format(const cv::Size &s) : FormatBase(
+			s.width,
+			s.height,
+			ftl::traits::OpenCVType<T>::value) {}
+
+	explicit Format(const cv::InputArray &a) : FormatBase(
+			a.cols,
+			a.rows,
+			ftl::traits::OpenCVType<T>::value) {
+		CHECK(cvType == a.type());
+	}
+};
+
+}
+}
+
+#endif  // _FTL_RGBD_FORMAT_HPP_
diff --git a/components/rgbd-sources/include/ftl/rgbd/frame.hpp b/components/rgbd-sources/include/ftl/rgbd/frame.hpp
index a1822fd163174bf9a55a697fa7736c0ac3d9a5bb..5b796a9512efeb8800bbc3c2a8ce4a154a2be296 100644
--- a/components/rgbd-sources/include/ftl/rgbd/frame.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/frame.hpp
@@ -3,134 +3,225 @@
 #define _FTL_RGBD_FRAME_HPP_
 
 #include <ftl/configuration.hpp>
+#include <ftl/exception.hpp>
 #include <opencv2/core.hpp>
 #include <opencv2/core/cuda.hpp>
 
-namespace ftl {
-namespace rgbd {
-
-typedef unsigned int channel_t;
-
-static const channel_t kChanNone = 0;
-static const channel_t kChanColour = 0x0001;
-static const channel_t kChanLeft = 0x0001;		// CV_8UC3
-static const channel_t kChanDepth = 0x0002;		// CV_32FC1
-static const channel_t kChanRight = 0x0004;		// CV_8UC3
-static const channel_t kChanDisparity = 0x0008; // CV_32FC1
-static const channel_t kChanDeviation = 0x0010;
-static const channel_t kChanNormals = 0x0020;
-static const channel_t kChanConfidence = 0x0040;
-static const channel_t kChanFlow = 0x0080;		// CV_16SC2 (format 10.5) from NVOF
-static const channel_t kChanEnergy = 0x0100;
+#include <ftl/rgbd/channels.hpp>
+#include <ftl/rgbd/format.hpp>
+#include <ftl/codecs/bitrates.hpp>
 
-// should l/r gray be removed (not that expensive to re-calculate if needed)?
-static const channel_t kChanLeftGray = 0x0200;	// CV_8UC1
-static const channel_t kChanRightGray = 0x0400;	// CV_8UC1
+#include <ftl/cuda_common.hpp>
 
-static const channel_t kChanOverlay1 = 0x1000;
+#include <type_traits>
 
-// maximum number of available channels
-static const unsigned int n_channels = 13;
-
-inline bool isFloatChannel(ftl::rgbd::channel_t chan) {
-	return (chan == ftl::rgbd::kChanDepth || chan == ftl::rgbd::kChanEnergy);
-}
+namespace ftl {
+namespace rgbd {
 
 // TODO:	interpolation for scaling depends on channel type;
 //			NN for depth/disparity/optflow, linear/cubic/etc. for RGB
 
 class Frame;
 
+/**
+ * Manage a set of image channels corresponding to a single camera frame.
+ */
 class Frame {
 public:
-	Frame() :	channels_host_(n_channels),
-				channels_gpu_(n_channels),
-				available_(n_channels, 0)
-	{}
+	Frame() {}
+
+	// Prevent frame copy, instead use a move.
+	//Frame(const Frame &)=delete;
+	//Frame &operator=(const Frame &)=delete;
+
+	void download(ftl::rgbd::Channel c, cv::cuda::Stream& stream=cv::cuda::Stream::Null());
+	void upload(ftl::rgbd::Channel c, cv::cuda::Stream& stream=cv::cuda::Stream::Null());
+	void download(ftl::rgbd::Channels c, cv::cuda::Stream& stream=cv::cuda::Stream::Null());
+	void upload(ftl::rgbd::Channels c, cv::cuda::Stream& stream=cv::cuda::Stream::Null());
+
+	/**
+	 * Create a channel with a given format. This will discard any existing
+	 * data associated with the channel and ensure all data structures and
+	 * memory allocations match the new format.
+	 */
+	template <typename T> T &create(ftl::rgbd::Channel c, const ftl::rgbd::FormatBase &f);
+
+	/**
+	 * Create a channel but without any format.
+	 */
+	template <typename T> T &create(ftl::rgbd::Channel c);
 
-	/* @brief	Reset all channels without releasing memory.
+	/**
+	 * Create a CUDA texture object for a channel. This version takes a format
+	 * argument to also create (or recreate) the associated GpuMat.
 	 */
-	void reset()
-	{
-		std::fill(available_.begin(), available_.end(), 0);
+	template <typename T>
+	ftl::cuda::TextureObject<T> &createTexture(ftl::rgbd::Channel c, const ftl::rgbd::Format<T> &f);
+
+	/**
+	 * Create a CUDA texture object for a channel. With this version the GpuMat
+	 * must already exist and be of the correct type.
+	 */
+	template <typename T>
+	ftl::cuda::TextureObject<T> &createTexture(ftl::rgbd::Channel c);
+
+	/**
+	 * Reset all channels without releasing memory.
+	 */
+	void reset();
+
+	/**
+	 * Is there valid data in channel (either host or gpu).
+	 */
+	inline bool hasChannel(ftl::rgbd::Channel channel) const {
+		return channels_.has(channel);
 	}
 
-	/* @brief	Is there valid data in channel (either host or gpu).
+	/**
+	 * Is the channel data currently located on GPU. This also returns false if
+	 * the channel does not exist.
 	 */
-	bool hasChannel(const ftl::rgbd::channel_t& channel)
-	{
-		return (channel == ftl::rgbd::kChanNone) ? true : available_[_channelIdx(channel)];
+	inline bool isGPU(ftl::rgbd::Channel channel) const {
+		return channels_.has(channel) && gpu_.has(channel);
 	}
 
-	/* @brief	Method to get reference to the channel content
+	/**
+	 * Is the channel data currently located on CPU memory. This also returns
+	 * false if the channel does not exist.
+	 */
+	inline bool isCPU(ftl::rgbd::Channel channel) const {
+		return channels_.has(channel) && !gpu_.has(channel);
+	}
+
+	/**
+	 * Method to get reference to the channel content.
 	 * @param	Channel type
-	 * @param	CUDA stream
-	 * @returns	Const reference to channel data
+	 * @return	Const reference to channel data
 	 * 
 	 * Result is valid only if hasChannel() is true. Host/Gpu transfer is
-	 * performed, if necessary, but only once unless channel contents is
-	 * changed by calling setChannel(). Return value valid only if
-	 * hasChannel(channel) is true.
+	 * performed, if necessary, but with a warning since an explicit upload or
+	 * download should be used.
 	 */
-	template <typename T> const T& getChannel(const ftl::rgbd::channel_t& channel, cv::cuda::Stream& stream);
-	template <typename T> const T& getChannel(const ftl::rgbd::channel_t& channel);
+	template <typename T> const T& get(ftl::rgbd::Channel channel) const;
 
-	/* @brief	Method to set/modify channel content
+	/**
+	 * Method to get reference to the channel content.
 	 * @param	Channel type
-	 * @returns	Reference to channel data
-	 * 
-	 * Returns non-const reference to channel memory. Invalidates other copies
-	 * of the data (host/gpu) for the specified channel, next time getChannel()
-	 * is called a memory transfer may occur.
+	 * @return	Reference to channel data
 	 * 
-	 * NOTE:	If user of setChannel<T>() wants to modify contents instead of
-	 * 			replacing them, getChannel<T>() needs to be called first to
-	 * 			ensure there is valid contents in the returned reference!
-	 * 			(TODO: interface could be improved)
+	 * Result is valid only if hasChannel() is true. Host/Gpu transfer is
+	 * performed, if necessary, but with a warning since an explicit upload or
+	 * download should be used.
 	 */
-	template <typename T> T& setChannel(const ftl::rgbd::channel_t& channel);
+	template <typename T> T& get(ftl::rgbd::Channel channel);
+
+	template <typename T> const ftl::cuda::TextureObject<T> &getTexture(ftl::rgbd::Channel) const;
+	template <typename T> ftl::cuda::TextureObject<T> &getTexture(ftl::rgbd::Channel);
 
 private:
+	struct ChannelData {
+		cv::Mat host;
+		cv::cuda::GpuMat gpu;
+		ftl::cuda::TextureObjectBase tex;
+	};
+
+	ChannelData data_[Channels::kMax];
 
-	static size_t _channelIdx(const ftl::rgbd::channel_t& channel)
-	{
-		switch(channel)
-		{
-			case kChanNone:				return 0;
-			case kChanLeft:				return 1;
-			case kChanDepth:			return 2;
-			case kChanRight:			return 3;
-			case kChanDisparity:		return 4;
-			case kChanDeviation:		return 5;
-			case kChanNormals:			return 6;
-			case kChanConfidence:		return 7;
-			case kChanFlow:				return 8;
-			case kChanEnergy:			return 9;
-			case kChanLeftGray:			return 11;
-			case kChanRightGray:		return 12;
-			// should not happen (error); returned index is kChanNone
-			default:					return 0;
-		}
+	ftl::rgbd::Channels channels_;	// Does it have a channel
+	ftl::rgbd::Channels gpu_;		// Is the channel on a GPU
+
+	inline ChannelData &_get(ftl::rgbd::Channel c) { return data_[static_cast<unsigned int>(c)]; }
+	inline const ChannelData &_get(ftl::rgbd::Channel c) const { return data_[static_cast<unsigned int>(c)]; }
+};
+
+// Specialisations
+
+template<> const cv::Mat& Frame::get(ftl::rgbd::Channel channel) const;
+template<> const cv::cuda::GpuMat& Frame::get(ftl::rgbd::Channel channel) const;
+template<> cv::Mat& Frame::get(ftl::rgbd::Channel channel);
+template<> cv::cuda::GpuMat& Frame::get(ftl::rgbd::Channel channel);
+
+template <> cv::Mat &Frame::create(ftl::rgbd::Channel c, const ftl::rgbd::FormatBase &);
+template <> cv::cuda::GpuMat &Frame::create(ftl::rgbd::Channel c, const ftl::rgbd::FormatBase &);
+template <> cv::Mat &Frame::create(ftl::rgbd::Channel c);
+template <> cv::cuda::GpuMat &Frame::create(ftl::rgbd::Channel c);
+
+template <typename T>
+ftl::cuda::TextureObject<T> &Frame::getTexture(ftl::rgbd::Channel c) {
+	if (!channels_.has(c)) throw ftl::exception("Texture channel does not exist");
+	if (!gpu_.has(c)) throw ftl::exception("Texture channel is not on GPU");
+
+	auto &m = _get(c);
+
+	if (m.tex.cvType() != ftl::traits::OpenCVType<T>::value || m.tex.width() != m.gpu.cols || m.tex.height() != m.gpu.rows || m.gpu.type() != m.tex.cvType()) {
+		throw ftl::exception("Texture has not been created properly for this channel");
 	}
 
-	std::vector<cv::Mat> channels_host_;
-	std::vector<cv::cuda::GpuMat> channels_gpu_;
+	return ftl::cuda::TextureObject<T>::cast(m.tex);
+}
 
-	// bitmasks for each channel stored in available_
-	static const uint mask_host = 1;
-	static const uint mask_gpu = 2;
+template <typename T>
+ftl::cuda::TextureObject<T> &Frame::createTexture(ftl::rgbd::Channel c, const ftl::rgbd::Format<T> &f) {
+	if (!channels_.has(c)) channels_ += c;
+	if (!gpu_.has(c)) gpu_ += c;
 
-	std::vector<uint> available_;
-};
+	auto &m = _get(c);
 
-template<> const cv::Mat& Frame::getChannel(const ftl::rgbd::channel_t& channel, cv::cuda::Stream& stream);
-template<> const cv::cuda::GpuMat& Frame::getChannel(const ftl::rgbd::channel_t& channel, cv::cuda::Stream& stream);
+	if (f.empty()) {
+		throw ftl::exception("createTexture needs a non-empty format");
+	} else {
+		m.gpu.create(f.size(), f.cvType);
+	}
 
-template<> const cv::Mat& Frame::getChannel(const ftl::rgbd::channel_t& channel);
-template<> const cv::cuda::GpuMat& Frame::getChannel(const ftl::rgbd::channel_t& channel);
+	if (m.gpu.type() != ftl::traits::OpenCVType<T>::value) {
+		throw ftl::exception("Texture type does not match underlying data type");
+	}
+
+	// TODO: Check tex cvType
 
-template<> cv::Mat& Frame::setChannel(const ftl::rgbd::channel_t& channel);
-template<> cv::cuda::GpuMat& Frame::setChannel(const ftl::rgbd::channel_t& channel);
+	if (m.tex.devicePtr() == nullptr) {
+		LOG(INFO) << "Creating texture object";
+		m.tex = ftl::cuda::TextureObject<T>(m.gpu);
+	} else if (m.tex.cvType() != ftl::traits::OpenCVType<T>::value || m.tex.width() != m.gpu.cols || m.tex.height() != m.gpu.rows) {
+		LOG(INFO) << "Recreating texture object";
+		m.tex.free();
+		m.tex = ftl::cuda::TextureObject<T>(m.gpu);
+	}
+
+	return ftl::cuda::TextureObject<T>::cast(m.tex);
+}
+
+template <typename T>
+ftl::cuda::TextureObject<T> &Frame::createTexture(ftl::rgbd::Channel c) {
+	if (!channels_.has(c)) throw ftl::exception("createTexture needs a format if the channel does not exist");
+
+	auto &m = _get(c);
+
+	if (isCPU(c) && !m.host.empty()) {
+		m.gpu.create(m.host.size(), m.host.type());
+		// TODO: Should this upload to GPU or not?
+		//gpu_ += c;
+	} else if (isCPU(c) || (isGPU(c) && m.gpu.empty())) {
+		throw ftl::exception("createTexture needs a format if no memory is allocated");
+	}
+
+	if (m.gpu.type() != ftl::traits::OpenCVType<T>::value) {
+		throw ftl::exception("Texture type does not match underlying data type");
+	}
+
+	// TODO: Check tex cvType
+
+	if (m.tex.devicePtr() == nullptr) {
+		LOG(INFO) << "Creating texture object";
+		m.tex = ftl::cuda::TextureObject<T>(m.gpu);
+	} else if (m.tex.cvType() != ftl::traits::OpenCVType<T>::value || m.tex.width() != m.gpu.cols || m.tex.height() != m.gpu.rows || m.tex.devicePtr() != m.gpu.data) {
+		LOG(INFO) << "Recreating texture object";
+		m.tex.free();
+		m.tex = ftl::cuda::TextureObject<T>(m.gpu);
+	}
+
+	return ftl::cuda::TextureObject<T>::cast(m.tex);
+}
 
 }
 }
diff --git a/components/rgbd-sources/include/ftl/rgbd/group.hpp b/components/rgbd-sources/include/ftl/rgbd/group.hpp
index e4ffb5984e625b1b9859a3f193a7f4b44c956684..0ded29e80b7d2fa01ad656c2fbb3b8865b726a70 100644
--- a/components/rgbd-sources/include/ftl/rgbd/group.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/group.hpp
@@ -1,6 +1,7 @@
 #ifndef _FTL_RGBD_GROUP_HPP_
 #define _FTL_RGBD_GROUP_HPP_
 
+#include <ftl/cuda_util.hpp>
 #include <ftl/threads.hpp>
 #include <ftl/timer.hpp>
 #include <ftl/rgbd/frame.hpp>
diff --git a/components/rgbd-sources/include/ftl/rgbd/source.hpp b/components/rgbd-sources/include/ftl/rgbd/source.hpp
index 1106d76220e676a3e7e36c5db18db9596a0f91d9..07391d76f10f4eec69f4a7df97123dfc59270a0c 100644
--- a/components/rgbd-sources/include/ftl/rgbd/source.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/source.hpp
@@ -1,10 +1,11 @@
 #ifndef _FTL_RGBD_SOURCE_HPP_
 #define _FTL_RGBD_SOURCE_HPP_
 
+#include <ftl/cuda_util.hpp>
 #include <ftl/configuration.hpp>
 #include <ftl/rgbd/camera.hpp>
 #include <ftl/threads.hpp>
-//#include <ftl/net/universe.hpp>
+#include <ftl/net/universe.hpp>
 #include <ftl/uri.hpp>
 #include <ftl/rgbd/detail/source.hpp>
 #include <opencv2/opencv.hpp>
@@ -65,9 +66,9 @@ class Source : public ftl::Configurable {
 	/**
 	 * Change the second channel source.
 	 */
-	bool setChannel(channel_t c);
+	bool setChannel(ftl::rgbd::Channel c);
 
-	channel_t getChannel() const { return channel_; }
+	ftl::rgbd::Channel getChannel() const { return channel_; }
 
 	/**
 	 * Perform the hardware or virtual frame grab operation. This should be
@@ -151,7 +152,7 @@ class Source : public ftl::Configurable {
 		else return params_;
 	}
 
-	const Camera parameters(channel_t) const;
+	const Camera parameters(ftl::rgbd::Channel) const;
 
 	cv::Mat cameraMatrix() const;
 
@@ -224,7 +225,7 @@ class Source : public ftl::Configurable {
 	SHARED_MUTEX mutex_;
 	bool paused_;
 	bool bullet_;
-	channel_t channel_;
+	ftl::rgbd::Channel channel_;
 	cudaStream_t stream_;
 	int64_t timestamp_;
 	std::function<void(int64_t, cv::Mat &, cv::Mat &)> callback_;
diff --git a/components/rgbd-sources/include/qsort.h b/components/rgbd-sources/include/qsort.h
new file mode 100644
index 0000000000000000000000000000000000000000..62a76b836c1b13861fc8a5a12ff0fc0eb7936f8a
--- /dev/null
+++ b/components/rgbd-sources/include/qsort.h
@@ -0,0 +1,186 @@
+/*
+ * Copyright (c) 2013, 2017 Alexey Tourbin
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.  IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+/*
+ * This is a traditional Quicksort implementation which mostly follows
+ * [Sedgewick 1978].  Sorting is performed entirely on array indices,
+ * while actual access to the array elements is abstracted out with the
+ * user-defined `LESS` and `SWAP` primitives.
+ *
+ * Synopsis:
+ *	QSORT(N, LESS, SWAP);
+ * where
+ *	N - the number of elements in A[];
+ *	LESS(i, j) - compares A[i] to A[j];
+ *	SWAP(i, j) - exchanges A[i] with A[j].
+ */
+
+#ifndef QSORT_H
+#define QSORT_H
+
+/* Sort 3 elements. */
+#define Q_SORT3(q_a1, q_a2, q_a3, Q_LESS, Q_SWAP) \
+do {					\
+    if (Q_LESS(q_a2, q_a1)) {		\
+	if (Q_LESS(q_a3, q_a2))		\
+	    Q_SWAP(q_a1, q_a3);		\
+	else {				\
+	    Q_SWAP(q_a1, q_a2);		\
+	    if (Q_LESS(q_a3, q_a2))	\
+		Q_SWAP(q_a2, q_a3);	\
+	}				\
+    }					\
+    else if (Q_LESS(q_a3, q_a2)) {	\
+	Q_SWAP(q_a2, q_a3);		\
+	if (Q_LESS(q_a2, q_a1))		\
+	    Q_SWAP(q_a1, q_a2);		\
+    }					\
+} while (0)
+
+/* Partition [q_l,q_r] around a pivot.  After partitioning,
+ * [q_l,q_j] are the elements that are less than or equal to the pivot,
+ * while [q_i,q_r] are the elements greater than or equal to the pivot. */
+#define Q_PARTITION(q_l, q_r, q_i, q_j, Q_UINT, Q_LESS, Q_SWAP)		\
+do {									\
+    /* The middle element, not to be confused with the median. */	\
+    Q_UINT q_m = q_l + ((q_r - q_l) >> 1);				\
+    /* Reorder the second, the middle, and the last items.		\
+     * As [Edelkamp Weiss 2016] explain, using the second element	\
+     * instead of the first one helps avoid bad behaviour for		\
+     * decreasingly sorted arrays.  This method is used in recent	\
+     * versions of gcc's std::sort, see gcc bug 58437#c13, although	\
+     * the details are somewhat different (cf. #c14). */		\
+    Q_SORT3(q_l + 1, q_m, q_r, Q_LESS, Q_SWAP);				\
+    /* Place the median at the beginning. */				\
+    Q_SWAP(q_l, q_m);							\
+    /* Partition [q_l+2, q_r-1] around the median which is in q_l.	\
+     * q_i and q_j are initially off by one, they get decremented	\
+     * in the do-while loops. */					\
+    q_i = q_l + 1; q_j = q_r;						\
+    while (1) {								\
+	do q_i++; while (Q_LESS(q_i, q_l));				\
+	do q_j--; while (Q_LESS(q_l, q_j));				\
+	if (q_i >= q_j) break; /* Sedgewick says "until j < i" */	\
+	Q_SWAP(q_i, q_j);						\
+    }									\
+    /* Compensate for the i==j case. */					\
+    q_i = q_j + 1;							\
+    /* Put the median to its final place. */				\
+    Q_SWAP(q_l, q_j);							\
+    /* The median is not part of the left subfile. */			\
+    q_j--;								\
+} while (0)
+
+/* Insertion sort is applied to small subfiles - this is contrary to
+ * Sedgewick's suggestion to run a separate insertion sort pass after
+ * the partitioning is done.  The reason I don't like a separate pass
+ * is that it triggers extra comparisons, because it can't see that the
+ * medians are already in their final positions and need not be rechecked.
+ * Since I do not assume that comparisons are cheap, I also do not try
+ * to eliminate the (q_j > q_l) boundary check. */
+#define Q_INSERTION_SORT(q_l, q_r, Q_UINT, Q_LESS, Q_SWAP)		\
+do {									\
+    Q_UINT q_i, q_j;							\
+    /* For each item starting with the second... */			\
+    for (q_i = q_l + 1; q_i <= q_r; q_i++)				\
+    /* move it down the array so that the first part is sorted. */	\
+    for (q_j = q_i; q_j > q_l && (Q_LESS(q_j, q_j - 1)); q_j--)		\
+	Q_SWAP(q_j, q_j - 1);						\
+} while (0)
+
+/* When the size of [q_l,q_r], i.e. q_r-q_l+1, is greater than or equal to
+ * Q_THRESH, the algorithm performs recursive partitioning.  When the size
+ * drops below Q_THRESH, the algorithm switches to insertion sort.
+ * The minimum valid value is probably 5 (with 5 items, the second and
+ * the middle items, the middle itself being rounded down, are distinct). */
+#define Q_THRESH 16
+
+/* The main loop. */
+#define Q_LOOP(Q_UINT, Q_N, Q_LESS, Q_SWAP)				\
+do {									\
+    Q_UINT q_l = 0;							\
+    Q_UINT q_r = (Q_N) - 1;						\
+    Q_UINT q_sp = 0; /* the number of frames pushed to the stack */	\
+    struct { Q_UINT q_l, q_r; }						\
+	/* On 32-bit platforms, to sort a "char[3GB+]" array,		\
+	 * it may take full 32 stack frames.  On 64-bit CPUs,		\
+	 * though, the address space is limited to 48 bits.		\
+	 * The usage is further reduced if Q_N has a 32-bit type. */	\
+	q_st[sizeof(Q_UINT) > 4 && sizeof(Q_N) > 4 ? 48 : 32];		\
+    while (1) {								\
+	if (q_r - q_l + 1 >= Q_THRESH) {				\
+	    Q_UINT q_i, q_j;						\
+	    Q_PARTITION(q_l, q_r, q_i, q_j, Q_UINT, Q_LESS, Q_SWAP);	\
+	    /* Now have two subfiles: [q_l,q_j] and [q_i,q_r].		\
+	     * Dealing with them depends on which one is bigger. */	\
+	    if (q_j - q_l >= q_r - q_i)					\
+		Q_SUBFILES(q_l, q_j, q_i, q_r);				\
+	    else							\
+		Q_SUBFILES(q_i, q_r, q_l, q_j);				\
+	}								\
+	else {								\
+	    Q_INSERTION_SORT(q_l, q_r, Q_UINT, Q_LESS, Q_SWAP);		\
+	    /* Pop subfiles from the stack, until it gets empty. */	\
+	    if (q_sp == 0) break;					\
+	    q_sp--;							\
+	    q_l = q_st[q_sp].q_l;					\
+	    q_r = q_st[q_sp].q_r;					\
+	}								\
+    }									\
+} while (0)
+
+/* The missing part: dealing with subfiles.
+ * Assumes that the first subfile is not smaller than the second. */
+#define Q_SUBFILES(q_l1, q_r1, q_l2, q_r2)				\
+do {									\
+    /* If the second subfile is only a single element, it needs		\
+     * no further processing.  The first subfile will be processed	\
+     * on the next iteration (both subfiles cannot be only a single	\
+     * element, due to Q_THRESH). */					\
+    if (q_l2 == q_r2) {							\
+	q_l = q_l1;							\
+	q_r = q_r1;							\
+    }									\
+    else {								\
+	/* Otherwise, both subfiles need processing.			\
+	 * Push the larger subfile onto the stack. */			\
+	q_st[q_sp].q_l = q_l1;						\
+	q_st[q_sp].q_r = q_r1;						\
+	q_sp++;								\
+	/* Process the smaller subfile on the next iteration. */	\
+	q_l = q_l2;							\
+	q_r = q_r2;							\
+    }									\
+} while (0)
+
+/* And now, ladies and gentlemen, may I proudly present to you... */
+#define QSORT(Q_N, Q_LESS, Q_SWAP)					\
+do {									\
+    if ((Q_N) > 1)							\
+	/* We could check sizeof(Q_N) and use "unsigned", but at least	\
+	 * on x86_64, this has the performance penalty of up to 5%. */	\
+	Q_LOOP(unsigned long, Q_N, Q_LESS, Q_SWAP);			\
+} while (0)
+
+#endif
+
+/* ex:set ts=8 sts=4 sw=4 noet: */
\ No newline at end of file
diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
index 782338fc2be41d56a4d6fcd4f4920f6d920e663f..5f8921bda0e562bcc26b454d750a35294ed75537 100644
--- a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
+++ b/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp
@@ -7,6 +7,8 @@
 using ftl::algorithms::FixstarsSGM;
 using cv::Mat;
 using cv::cuda::GpuMat;
+using ftl::rgbd::Channel;
+using ftl::rgbd::Format;
 
 //static ftl::Disparity::Register fixstarssgm("libsgm", FixstarsSGM::create);
 
@@ -78,14 +80,9 @@ void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream)
 		cv::cuda::cvtColor(rgb, gray, cv::COLOR_BGR2GRAY, 0, stream);
 	}*/
 
-	const auto &l = frame.getChannel<GpuMat>(ftl::rgbd::kChanLeft, stream);
-	const auto &r = frame.getChannel<GpuMat>(ftl::rgbd::kChanRight, stream);
-	auto &disp = frame.setChannel<GpuMat>(ftl::rgbd::kChanDisparity);
-
-	if (disp.size() != l.size())
-	{
-		disp = GpuMat(l.size(), CV_32FC1);
-	}
+	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_)
@@ -131,11 +128,7 @@ void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream)
 	dispt_scaled.convertTo(disp, CV_32F, 1.0f / 16.0f, stream);
 
 #ifdef HAVE_OPTFLOW
-	if (use_off_)
-	{
-		frame.getChannel<Mat>(ftl::rgbd::kChanDisparity);
-		off_.filter(frame.setChannel<Mat>(ftl::rgbd::kChanDisparity), Mat(lbw_));
-	}
+	if (use_off_) { off_.filter(frame, stream); }
 #endif
 }
 
diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
index 039db0c874d8d816b91d447a6254c79fd5a43304..d2c0c1d2a8fd459695bb02c9f66f17e423dc9fa5 100644
--- a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
+++ b/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp
@@ -5,6 +5,7 @@
 #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>
diff --git a/components/rgbd-sources/src/algorithms/offilter.cu b/components/rgbd-sources/src/algorithms/offilter.cu
new file mode 100644
index 0000000000000000000000000000000000000000..6feee5ae1daf9fc8b4b165370dbb8646b1d7b8a1
--- /dev/null
+++ b/components/rgbd-sources/src/algorithms/offilter.cu
@@ -0,0 +1,91 @@
+#include <ftl/cuda_common.hpp>
+#include <ftl/rgbd/camera.hpp>
+#include <opencv2/core/cuda_stream_accessor.hpp>
+#include <qsort.h>
+
+__device__ void quicksort(float A[], size_t n)
+{
+	float tmp;
+	#define LESS(i, j) A[i] < A[j]
+	#define SWAP(i, j) tmp = A[i], A[i] = A[j], A[j] = tmp
+	QSORT(n, LESS, SWAP);
+}
+
+template<typename T>
+__device__  static bool inline isValidDisparity(T d) { return (0.0 < d) && (d < 256.0); } // TODO
+
+static const int max_history = 32; // TODO dynamic shared memory
+
+__global__ void temporal_median_filter_kernel(
+	cv::cuda::PtrStepSz<float> disp,
+	cv::cuda::PtrStepSz<int16_t> optflow,
+	cv::cuda::PtrStepSz<float> history,
+	int n_max,
+	int16_t threshold, // fixed point 10.5
+	float granularity  // 4 for Turing
+)
+{
+	float sorted[max_history]; // TODO: dynamic shared memory
+	for (STRIDE_Y(y, disp.rows)) {
+	for (STRIDE_X(x, disp.cols)) {
+
+		int flowx = optflow(round(y / granularity), 2 * round(x / granularity));
+		int flowy = optflow(round(y / granularity), 2 * round(x / granularity) + 1);
+
+		if ((abs(flowx) + abs(flowy)) > threshold)
+		{
+			// last element in history[x][y][t]
+			history(y, (x + 1) * n_max - 1) = 0.0;
+			return;
+		}
+
+		int count = history(y, (x + 1) * n_max - 1);
+		int n = count % (n_max - 1);
+
+		if (isValidDisparity(disp(y, x)))
+		{
+			history(y, (x + 1) * n_max - 1) += 1.0;
+			count++;
+			history(y, x * n_max + n) = disp(y, x);
+		}
+
+		int n_end = count;
+		if (n_end >= n_max)	{ n_end = n_max - 1; }
+
+		if (n_end != 0)
+		{
+			for (size_t i = 0; i < n_end; i++)
+			{
+				sorted[i] = history(y, x * n_max + i);
+			}
+
+			quicksort(sorted, n_end);
+			disp(y, x) = sorted[n_end / 2];
+		}
+	}}
+}
+
+namespace ftl {
+namespace cuda {
+	
+void optflow_filter(cv::cuda::GpuMat &disp, const cv::cuda::GpuMat &optflow,
+					cv::cuda::GpuMat &history, int n, float threshold,
+					cv::cuda::Stream &stream)
+{
+	dim3 grid(1, 1, 1);
+	dim3 threads(128, 1, 1);
+	grid.x = cv::cuda::device::divUp(disp.cols, 128);
+	grid.y = cv::cuda::device::divUp(disp.rows, 1);
+
+	// TODO: dynamic shared memory
+	temporal_median_filter_kernel<<<grid, threads, 0, cv::cuda::StreamAccessor::getStream(stream)>>>
+		(	disp, optflow, history, n,
+			round(threshold * (1 << 5)),	// TODO: documentation; 10.5 format
+			4								// TODO: (4 pixels granularity for Turing)
+		);
+
+	cudaSafeCall(cudaGetLastError());
+}
+
+}
+}
\ No newline at end of file
diff --git a/components/rgbd-sources/src/cuda_algorithms.hpp b/components/rgbd-sources/src/cuda_algorithms.hpp
index 0aa7399c0a24035bdbbb0442b3c429ddd03d145c..439c16cfc21fef08086bb69b7e84b1c8b49fec74 100644
--- a/components/rgbd-sources/src/cuda_algorithms.hpp
+++ b/components/rgbd-sources/src/cuda_algorithms.hpp
@@ -41,6 +41,9 @@ namespace cuda {
 	void disparity_to_depth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth,
 				const ftl::rgbd::Camera &c, cv::cuda::Stream &stream);
 
+	void optflow_filter(cv::cuda::GpuMat &disp, const cv::cuda::GpuMat &optflow,
+						cv::cuda::GpuMat &history, int n_max, float threshold,
+						cv::cuda::Stream &stream);
 
 }
 }
diff --git a/components/rgbd-sources/src/disparity.hpp b/components/rgbd-sources/src/disparity.hpp
index 2ab8223ca97f14752265be86ccf0ace0554eb20e..44215871d37b2944c08d072d63afd5bf871082e4 100644
--- a/components/rgbd-sources/src/disparity.hpp
+++ b/components/rgbd-sources/src/disparity.hpp
@@ -48,10 +48,11 @@ class Disparity : public ftl::Configurable {
 	virtual void compute(Frame &frame, cv::cuda::Stream &stream)=0;
 	virtual void compute(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &disp, cv::cuda::Stream &stream)
 	{
-		ftl::rgbd::Frame frame;
-		frame.setChannel<cv::cuda::GpuMat>(kChanLeft) = l;
-		frame.setChannel<cv::cuda::GpuMat>(kChanRight) = r;
-		frame.setChannel<cv::cuda::GpuMat>(kChanDisparity) = disp;
+		// FIXME: What were these for?
+		//ftl::rgbd::Frame frame;
+		//frame.create<cv::cuda::GpuMat>(ftl::rgbd::Channel::Left) = l;
+		//frame.create<cv::cuda::GpuMat>(ftl::rgbd::Channel::Right) = r;
+		//frame.create<cv::cuda::GpuMat>(ftl::rgbd::Channel::Disparity) = disp;
 	}
 
 	/**
diff --git a/components/rgbd-sources/src/frame.cpp b/components/rgbd-sources/src/frame.cpp
index 8145280cc83d24347d9bb2fc07a5a9546bbe5dd7..4886ff3cbde3b4835b01ef71339fcf15fc6f16b2 100644
--- a/components/rgbd-sources/src/frame.cpp
+++ b/components/rgbd-sources/src/frame.cpp
@@ -1,68 +1,166 @@
 
 #include <ftl/rgbd/frame.hpp>
 
-namespace ftl {
-namespace rgbd {
-
-template<> const cv::Mat& Frame::getChannel(const ftl::rgbd::channel_t& channel, cv::cuda::Stream &stream)
-{
-	size_t idx = _channelIdx(channel);
-	if (!(available_[idx] & mask_host))
-	{
-		if (available_[idx] & mask_gpu)
-		{
-			channels_gpu_[idx].download(channels_host_[idx], stream);
-			available_[idx] |= mask_host;
+using ftl::rgbd::Frame;
+using ftl::rgbd::Channels;
+using ftl::rgbd::Channel;
+
+static cv::Mat none;
+static cv::cuda::GpuMat noneGPU;
+
+void Frame::reset() {
+	channels_.clear();
+	gpu_.clear();
+}
+
+void Frame::download(Channel c, cv::cuda::Stream& stream) {
+	download(Channels(c), stream);
+}
+
+void Frame::upload(Channel c, cv::cuda::Stream& stream) {
+	upload(Channels(c), stream);
+}
+
+void Frame::download(Channels c, cv::cuda::Stream& stream) {
+	for (size_t i=0u; i<Channels::kMax; ++i) {
+		if (c.has(i) && channels_.has(i) && gpu_.has(i)) {
+			data_[i].gpu.download(data_[i].host, stream);
+			gpu_ -= i;
 		}
 	}
+}
 
-	return channels_host_[idx];
+void Frame::upload(Channels c, cv::cuda::Stream& stream) {
+	for (size_t i=0u; i<Channels::kMax; ++i) {
+		if (c.has(i) && channels_.has(i) && !gpu_.has(i)) {
+			data_[i].gpu.upload(data_[i].host, stream);
+			gpu_ += i;
+		}
+	}
 }
 
-template<> const cv::Mat& Frame::getChannel(const ftl::rgbd::channel_t& channel)
-{
-	auto &stream = cv::cuda::Stream::Null();
-	auto &retval = getChannel<cv::Mat>(channel, stream);
-	stream.waitForCompletion();
-	return retval;
+template<> cv::Mat& Frame::get(ftl::rgbd::Channel channel) {
+	if (channel == Channel::None) {
+		DLOG(WARNING) << "Cannot get the None channel from a Frame";
+		none.release();
+		return none;
+	}
+
+	if (isGPU(channel)) {
+		download(Channels(channel));
+		LOG(WARNING) << "Getting GPU channel on CPU without explicit 'download'";
+	}
+
+	// Add channel if not already there
+	if (!channels_.has(channel)) {
+		throw ftl::exception("Frame channel does not exist");
+	}
+
+	return _get(channel).host;
 }
 
-template<> cv::Mat& Frame::setChannel(const ftl::rgbd::channel_t& channel)
-{
-	size_t idx = _channelIdx(channel);
-	available_[idx] = mask_host;
-	return channels_host_[idx];
+template<> cv::cuda::GpuMat& Frame::get(ftl::rgbd::Channel channel) {
+	if (channel == Channel::None) {
+		DLOG(WARNING) << "Cannot get the None channel from a Frame";
+		noneGPU.release();
+		return noneGPU;
+	}
+
+	if (isCPU(channel)) {
+		upload(Channels(channel));
+		LOG(WARNING) << "Getting CPU channel on GPU without explicit 'upload'";
+	}
+
+	// Add channel if not already there
+	if (!channels_.has(channel)) {
+		throw ftl::exception("Frame channel does not exist");
+	}
+
+	return _get(channel).gpu;
 }
 
-template<> const cv::cuda::GpuMat& Frame::getChannel(const ftl::rgbd::channel_t& channel, cv::cuda::Stream &stream)
-{
-	size_t idx = _channelIdx(channel);
-	if (!(available_[idx] & mask_gpu))
-	{
-		if (available_[idx] & mask_host)
-		{
-			channels_gpu_[idx].upload(channels_host_[idx], stream);
-			available_[idx] |= mask_gpu;
-		}
+template<> const cv::Mat& Frame::get(ftl::rgbd::Channel channel) const {
+	if (channel == Channel::None) {
+		LOG(FATAL) << "Cannot get the None channel from a Frame";
 	}
-	
-	return channels_gpu_[idx];
+
+	if (isGPU(channel)) {
+		LOG(FATAL) << "Getting GPU channel on CPU without explicit 'download'";
+	}
+
+	if (!channels_.has(channel)) throw ftl::exception("Frame channel does not exist");
+
+	return _get(channel).host;
+}
+
+template<> const cv::cuda::GpuMat& Frame::get(ftl::rgbd::Channel channel) const {
+	if (channel == Channel::None) {
+		LOG(FATAL) << "Cannot get the None channel from a Frame";
+	}
+
+	if (isCPU(channel)) {
+		LOG(FATAL) << "Getting CPU channel on GPU without explicit 'upload'";
+	}
+
+	// Add channel if not already there
+	if (!channels_.has(channel)) {
+		throw ftl::exception("Frame channel does not exist");
+	}
+
+	return _get(channel).gpu;
+}
+
+template <> cv::Mat &Frame::create(ftl::rgbd::Channel c, const ftl::rgbd::FormatBase &f) {
+	if (c == Channel::None) {
+		throw ftl::exception("Cannot create a None channel");
+	}
+	channels_ += c;
+	gpu_ -= c;
+
+	auto &m = _get(c).host;
+
+	if (!f.empty()) {
+		m.create(f.size(), f.cvType);
+	}
+
+	return m;
 }
 
-template<> const cv::cuda::GpuMat& Frame::getChannel(const ftl::rgbd::channel_t& channel)
-{
-	auto &stream = cv::cuda::Stream::Null();
-	auto &retval = getChannel<cv::cuda::GpuMat>(channel, stream);
-	stream.waitForCompletion();
-	return retval;
+template <> cv::cuda::GpuMat &Frame::create(ftl::rgbd::Channel c, const ftl::rgbd::FormatBase &f) {
+	if (c == Channel::None) {
+		throw ftl::exception("Cannot create a None channel");
+	}
+	channels_ += c;
+	gpu_ += c;
+
+	auto &m = _get(c).gpu;
+
+	if (!f.empty()) {
+		m.create(f.size(), f.cvType);
+	}
+
+	return m;
 }
 
-template<> cv::cuda::GpuMat& Frame::setChannel(const ftl::rgbd::channel_t& channel)
-{
-	size_t idx = _channelIdx(channel);
-	available_[idx] = mask_gpu;
-	return channels_gpu_[idx];
+template <> cv::Mat &Frame::create(ftl::rgbd::Channel c) {
+	if (c == Channel::None) {
+		throw ftl::exception("Cannot create a None channel");
+	}
+	channels_ += c;
+	gpu_ -= c;
+
+	auto &m = _get(c).host;
+	return m;
 }
 
+template <> cv::cuda::GpuMat &Frame::create(ftl::rgbd::Channel c) {
+	if (c == Channel::None) {
+		throw ftl::exception("Cannot create a None channel");
+	}
+	channels_ += c;
+	gpu_ += c;
+
+	auto &m = _get(c).gpu;
+	return m;
 }
-}
\ No newline at end of file
+
diff --git a/components/rgbd-sources/src/group.cpp b/components/rgbd-sources/src/group.cpp
index 57d770ba12db4f4b15aebf48cedd33aa2b880fa5..96ca3a82fd3e306656f047d4971ce4a29b00fe48 100644
--- a/components/rgbd-sources/src/group.cpp
+++ b/components/rgbd-sources/src/group.cpp
@@ -10,6 +10,7 @@ using ftl::rgbd::kFrameBufferSize;
 using std::vector;
 using std::chrono::milliseconds;
 using std::this_thread::sleep_for;
+using ftl::rgbd::Channel;
 
 Group::Group() : framesets_(kFrameBufferSize), head_(0) {
 	framesets_[0].timestamp = -1;
@@ -77,13 +78,13 @@ void Group::addSource(ftl::rgbd::Source *src) {
 				// Ensure channels match source mat format
 				//fs.channel1[ix].create(rgb.size(), rgb.type());
 				//fs.channel2[ix].create(depth.size(), depth.type());
-				fs.frames[ix].setChannel<cv::Mat>(ftl::rgbd::kChanColour).create(rgb.size(), rgb.type());
-				fs.frames[ix].setChannel<cv::Mat>(chan).create(depth.size(), depth.type());
+				fs.frames[ix].create<cv::Mat>(Channel::Colour, Format<uchar3>(rgb.size())); //.create(rgb.size(), rgb.type());
+				if (chan != Channel::None) fs.frames[ix].create<cv::Mat>(chan, ftl::rgbd::FormatBase(depth.cols, depth.rows, depth.type())); //.create(depth.size(), depth.type());
 
 				//cv::swap(rgb, fs.channel1[ix]);
 				//cv::swap(depth, fs.channel2[ix]);
-				cv::swap(rgb, fs.frames[ix].setChannel<cv::Mat>(ftl::rgbd::kChanColour));
-				cv::swap(depth, fs.frames[ix].setChannel<cv::Mat>(chan));
+				cv::swap(rgb, fs.frames[ix].get<cv::Mat>(Channel::Colour));
+				if (chan != Channel::None) cv::swap(depth, fs.frames[ix].get<cv::Mat>(chan));
 
 				++fs.count;
 				fs.mask |= (1 << ix);
diff --git a/components/rgbd-sources/src/net.cpp b/components/rgbd-sources/src/net.cpp
index 5c3c7ecb5dc3a11d0b4f96471ebe2eb8beef53d8..ba485c9402d888be0636902f3962cce2dd1e85ed 100644
--- a/components/rgbd-sources/src/net.cpp
+++ b/components/rgbd-sources/src/net.cpp
@@ -20,6 +20,7 @@ using std::vector;
 using std::this_thread::sleep_for;
 using std::chrono::milliseconds;
 using std::tuple;
+using ftl::rgbd::Channel;
 
 // ===== NetFrameQueue =========================================================
 
@@ -69,7 +70,7 @@ void NetFrameQueue::freeFrame(NetFrame &f) {
 
 // ===== NetSource =============================================================
 
-bool NetSource::_getCalibration(Universe &net, const UUID &peer, const string &src, ftl::rgbd::Camera &p, ftl::rgbd::channel_t chan) {
+bool NetSource::_getCalibration(Universe &net, const UUID &peer, const string &src, ftl::rgbd::Camera &p, ftl::rgbd::Channel chan) {
 	try {
 		while(true) {
 			auto [cap,buf] = net.call<tuple<unsigned int,vector<unsigned char>>>(peer_, "source_details", src, chan);
@@ -227,11 +228,11 @@ void NetSource::_recvPacket(short ttimeoff, const ftl::codecs::StreamPacket &spk
 	int64_t now = std::chrono::time_point_cast<std::chrono::milliseconds>(std::chrono::high_resolution_clock::now()).time_since_epoch().count();
 	if (!active_) return;
 
-	const ftl::rgbd::channel_t chan = host_->getChannel();
+	const ftl::rgbd::Channel chan = host_->getChannel();
 	int rchan = spkt.channel & 0x1;
 
 	// Ignore any unwanted second channel
-	if (chan == ftl::rgbd::kChanNone && rchan > 0) {
+	if (chan == ftl::rgbd::Channel::None && rchan > 0) {
 		LOG(INFO) << "Unwanted channel";
 		//return;
 		// TODO: Allow decode to be skipped
@@ -324,8 +325,8 @@ void NetSource::setPose(const Eigen::Matrix4d &pose) {
 	//Source::setPose(pose);
 }
 
-ftl::rgbd::Camera NetSource::parameters(ftl::rgbd::channel_t chan) {
-	if (chan == ftl::rgbd::kChanRight) {
+ftl::rgbd::Camera NetSource::parameters(ftl::rgbd::Channel chan) {
+	if (chan == ftl::rgbd::Channel::Right) {
 		auto uri = host_->get<string>("uri");
 		if (!uri) return params_;
 
@@ -340,7 +341,7 @@ ftl::rgbd::Camera NetSource::parameters(ftl::rgbd::channel_t chan) {
 void NetSource::_updateURI() {
 	UNIQUE_LOCK(mutex_,lk);
 	active_ = false;
-	prev_chan_ = ftl::rgbd::kChanNone;
+	prev_chan_ = ftl::rgbd::Channel::None;
 	auto uri = host_->get<string>("uri");
 
 	if (uri_.size() > 0) {
@@ -355,7 +356,7 @@ void NetSource::_updateURI() {
 		}
 		peer_ = *p;
 
-		has_calibration_ = _getCalibration(*host_->getNet(), peer_, *uri, params_, ftl::rgbd::kChanLeft);
+		has_calibration_ = _getCalibration(*host_->getNet(), peer_, *uri, params_, ftl::rgbd::Channel::Left);
 
 		host_->getNet()->bind(*uri, [this](short ttimeoff, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) {
 			//if (chunk == -1) {
@@ -395,7 +396,7 @@ bool NetSource::compute(int n, int b) {
 	// Send k frames before end to prevent unwanted pause
 	// Unless only a single frame is requested
 	if ((N_ <= maxN_/2 && maxN_ > 1) || N_ == 0) {
-		const ftl::rgbd::channel_t chan = host_->getChannel();
+		const ftl::rgbd::Channel chan = host_->getChannel();
 
 		N_ = maxN_;
 
diff --git a/components/rgbd-sources/src/net.hpp b/components/rgbd-sources/src/net.hpp
index 236ac6969759c7531c65681504b27aacae985d9d..51f31861fa3c9c39ea0cb53217e0fa3f764aeef3 100644
--- a/components/rgbd-sources/src/net.hpp
+++ b/components/rgbd-sources/src/net.hpp
@@ -39,7 +39,7 @@ class NetSource : public detail::Source {
 	bool isReady();
 
 	void setPose(const Eigen::Matrix4d &pose);
-	Camera parameters(channel_t chan);
+	Camera parameters(ftl::rgbd::Channel chan);
 
 	void reset();
 
@@ -57,7 +57,7 @@ class NetSource : public detail::Source {
 	int minB_;
 	int maxN_;
 	int default_quality_;
-	ftl::rgbd::channel_t prev_chan_;
+	ftl::rgbd::Channel prev_chan_;
 
 	ftl::rgbd::detail::ABRController abr_;
 	int last_bitrate_;
@@ -77,7 +77,7 @@ class NetSource : public detail::Source {
 
 	NetFrameQueue queue_;
 
-	bool _getCalibration(ftl::net::Universe &net, const ftl::UUID &peer, const std::string &src, ftl::rgbd::Camera &p, ftl::rgbd::channel_t chan);
+	bool _getCalibration(ftl::net::Universe &net, const ftl::UUID &peer, const std::string &src, ftl::rgbd::Camera &p, ftl::rgbd::Channel chan);
 	void _recv(const std::vector<unsigned char> &jpg, const std::vector<unsigned char> &d);
 	void _recvPacket(short ttimeoff, const ftl::codecs::StreamPacket &, const ftl::codecs::Packet &);
 	//void _recvChunk(int64_t frame, short ttimeoff, uint8_t bitrate, int chunk, const std::vector<unsigned char> &jpg, const std::vector<unsigned char> &d);
diff --git a/components/rgbd-sources/src/offilter.cpp b/components/rgbd-sources/src/offilter.cpp
index 03db4807a7f9fa045708d3cf17bf32556b7bf5b5..466aa9249517b91ac54726e821401e85272aa082 100644
--- a/components/rgbd-sources/src/offilter.cpp
+++ b/components/rgbd-sources/src/offilter.cpp
@@ -1,4 +1,5 @@
 #include "ftl/offilter.hpp"
+#include "cuda_algorithms.hpp"
 
 #ifdef HAVE_OPTFLOW
 
@@ -14,101 +15,27 @@ using std::vector;
 template<typename T> static bool inline isValidDisparity(T d) { return (0.0 < d) && (d < 256.0); } // TODO
 
 OFDisparityFilter::OFDisparityFilter(Size size, int n_frames, float threshold) :
-	n_(0), n_max_(n_frames), threshold_(threshold), size_(size)
+	n_max_(n_frames + 1), threshold_(threshold)
 {
+	CHECK((n_max_ > 1) && (n_max_ <= 32)) << "History length must be between 0 and 31!";
+	disp_old_ = cv::cuda::GpuMat(cv::Size(size.width * n_max_, size.height), CV_32FC1);
 	
-	disp_ = Mat::zeros(cv::Size(size.width * n_frames, size.height), CV_64FC1);
-	gray_ = Mat::zeros(size, CV_8UC1);
-
-	nvof_ = cv::cuda::NvidiaOpticalFlow_1_0::create(size.width, size.height,
+	/*nvof_ = cv::cuda::NvidiaOpticalFlow_1_0::create(size.width, size.height,
 													cv::cuda::NvidiaOpticalFlow_1_0::NV_OF_PERF_LEVEL_SLOW,
-													true, false, false, 0);
+													true, false, false, 0);*/
 	
 }
 
-void OFDisparityFilter::filter(Mat &disp, const Mat &gray)
+void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream)
 {
-
-	const int n = n_;
-	n_ = (n_ + 1) % n_max_;
-	
-	nvof_->calc(gray, gray_, flowxy_);
-	nvof_->upSampler(	flowxy_, size_.width, size_.height,
-						nvof_->getGridSize(), flowxy_up_);
-
-	CHECK(disp.type() == CV_32FC1);
-	CHECK(gray.type() == CV_8UC1);
-	CHECK(flowxy_up_.type() == CV_32FC2);
-
-	gray.copyTo(gray_);
-
-	vector<float> values(n_max_);
-
-	for (int y = 0; y < size_.height; y++)
-	{
-		float *D = disp_.ptr<float>(y);
-		float *d = disp.ptr<float>(y);
-		float *flow = flowxy_up_.ptr<float>(y);
-
-		for (int x = 0; x < size_.width; x++)
-		{
-			const float flow_l1 = abs(flow[2*x]) + abs(flow[2*x + 1]);
-
-			if (flow_l1 < threshold_)
-			{
-				values.clear();
-
-				if (isValidDisparity(d[x]))
-				{
-					bool updated = false;
-					for (int i = 0; i < n_max_; i++)
-					{
-						float &val = D[n_max_ * x + (n_max_ - i + n) % n_max_];
-						if (!isValidDisparity(val))
-						{
-							val = d[x];
-							updated = true;
-						}
-					}
-					if (!updated) { D[n_max_ * x + n] = d[x]; }
-				}
-
-				for (int i = 0; i < n_max_; i++)
-				{
-					float &val = D[n_max_ * x + i];
-					if (isValidDisparity(val)) { values.push_back(val); }
-				}
-
-				if (values.size() > 0) {
-					const auto median_it = values.begin() + values.size() / 2;
-					std::nth_element(values.begin(), median_it , values.end());
-					d[x] = *median_it;
-				}
-
-				/*
-				if (isValidDepth(d[x]) && isValidDepth(D[x]))
-				{
-					D[x] = D[x] * 0.66 + d[x] * (1.0 - 0.66);
-				}
-				if (isValidDepth(D[x]))
-				{
-					d[x] = D[x];
-				}
-				else
-				{
-					D[x] = d[x];
-				}
-				*/
-			}
-			else
-			{
-				for (int i = 0; i < n_max_; i++)
-				{
-					D[n_max_ * x + i] = 0.0;
-				}
-			}
-		}
-	}
+	frame.upload(Channel::Flow, stream);
+	const cv::cuda::GpuMat &optflow = frame.get<cv::cuda::GpuMat>(Channel::Flow);
+	//frame.get<cv::cuda::GpuMat>(Channel::Disparity);
+	stream.waitForCompletion();
+	if (optflow.empty()) { return; }
+
+	cv::cuda::GpuMat &disp = frame.create<cv::cuda::GpuMat>(Channel::Disparity);
+	ftl::cuda::optflow_filter(disp, optflow, disp_old_, n_max_, threshold_, stream);
 }
 
 #endif  // HAVE_OPTFLOW
diff --git a/components/rgbd-sources/src/source.cpp b/components/rgbd-sources/src/source.cpp
index 10c9210f183c8f51d0b1e5424f0e4e441321cd86..f52359be76ff3010961a6baada6252d2cd592e25 100644
--- a/components/rgbd-sources/src/source.cpp
+++ b/components/rgbd-sources/src/source.cpp
@@ -25,6 +25,7 @@ using ftl::rgbd::detail::NetSource;
 using ftl::rgbd::detail::ImageSource;
 using ftl::rgbd::detail::MiddleburySource;
 using ftl::rgbd::capability_t;
+using ftl::rgbd::Channel;
 
 Source::Source(ftl::config::json_t &cfg) : Configurable(cfg), pose_(Eigen::Matrix4d::Identity()), net_(nullptr) {
 	impl_ = nullptr;
@@ -227,7 +228,7 @@ capability_t Source::getCapabilities() const {
 
 void Source::reset() {
 	UNIQUE_LOCK(mutex_,lk);
-	channel_ = kChanNone;
+	channel_ = Channel::None;
 	if (impl_) delete impl_;
 	impl_ = _createImplementation();
 }
@@ -360,13 +361,13 @@ bool Source::thumbnail(cv::Mat &t) {
 	return !thumb_.empty();
 }
 
-bool Source::setChannel(ftl::rgbd::channel_t c) {
+bool Source::setChannel(ftl::rgbd::Channel c) {
 	channel_ = c;
 	// FIXME:(Nick) Verify channel is supported by this source...
 	return true;
 }
 
-const ftl::rgbd::Camera Source::parameters(ftl::rgbd::channel_t chan) const {
+const ftl::rgbd::Camera Source::parameters(ftl::rgbd::Channel chan) const {
 	return (impl_) ? impl_->parameters(chan) : parameters();
 }
 
diff --git a/components/rgbd-sources/src/stereovideo.cpp b/components/rgbd-sources/src/stereovideo.cpp
index ebc72d854e8d35a480f3d4ef5873e8b58d5bb086..6573f74f4d7cf1f3761f98a66c68c6963e10af31 100644
--- a/components/rgbd-sources/src/stereovideo.cpp
+++ b/components/rgbd-sources/src/stereovideo.cpp
@@ -12,6 +12,7 @@
 using ftl::rgbd::detail::Calibrate;
 using ftl::rgbd::detail::LocalSource;
 using ftl::rgbd::detail::StereoVideoSource;
+using ftl::rgbd::Channel;
 using std::string;
 
 StereoVideoSource::StereoVideoSource(ftl::rgbd::Source *host)
@@ -135,8 +136,8 @@ void StereoVideoSource::init(const string &file)
 	ready_ = true;
 }
 
-ftl::rgbd::Camera StereoVideoSource::parameters(ftl::rgbd::channel_t chan) {
-	if (chan == ftl::rgbd::kChanRight) {
+ftl::rgbd::Camera StereoVideoSource::parameters(Channel chan) {
+	if (chan == Channel::Right) {
 		cv::Mat q = calib_->getCameraMatrixRight();
 		ftl::rgbd::Camera params = {
 			q.at<double>(0,0),	// Fx
@@ -175,8 +176,8 @@ bool StereoVideoSource::capture(int64_t ts) {
 bool StereoVideoSource::retrieve() {
 	auto &frame = frames_[0];
 	frame.reset();
-	auto &left = frame.setChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanLeft);
-	auto &right = frame.setChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanRight);
+	auto &left = frame.create<cv::cuda::GpuMat>(Channel::Left);
+	auto &right = frame.create<cv::cuda::GpuMat>(Channel::Right);
 	lsrc_->get(left, right, calib_, stream2_);
 
 #ifdef HAVE_OPTFLOW
@@ -184,17 +185,18 @@ bool StereoVideoSource::retrieve() {
 	
 	if (use_optflow_)
 	{
-		auto &left_gray = frame.setChannel<cv::cuda::GpuMat>(kChanLeftGray);
-		auto &right_gray = frame.setChannel<cv::cuda::GpuMat>(kChanRightGray);
+		auto &left_gray = frame.create<cv::cuda::GpuMat>(Channel::LeftGray);
+		auto &right_gray = frame.create<cv::cuda::GpuMat>(Channel::RightGray);
 
 		cv::cuda::cvtColor(left, left_gray, cv::COLOR_BGR2GRAY, 0, stream2_);
 		cv::cuda::cvtColor(right, right_gray, cv::COLOR_BGR2GRAY, 0, stream2_);
 
-		if (frames_[1].hasChannel(kChanLeftGray))
+		if (frames_[1].hasChannel(Channel::LeftGray))
 		{
-			auto &left_gray_prev = frame.getChannel<cv::cuda::GpuMat>(kChanLeftGray, stream2_);
-			auto &optflow = frame.setChannel<cv::cuda::GpuMat>(kChanFlow);
-			nvof_->calc(left_gray, left_gray_prev, optflow_, stream2_);
+			//frames_[1].download(Channel::LeftGray);
+			auto &left_gray_prev = frames_[1].get<cv::cuda::GpuMat>(Channel::LeftGray);
+			auto &optflow = frame.create<cv::cuda::GpuMat>(Channel::Flow);
+			nvof_->calc(left_gray, left_gray_prev, optflow, stream2_);
 			// nvof_->upSampler() isn't implemented with CUDA
 			// cv::cuda::resize() does not work wiht 2-channel input
 			// cv::cuda::resize(optflow_, optflow, left.size(), 0.0, 0.0, cv::INTER_NEAREST, stream2_);
@@ -207,32 +209,33 @@ bool StereoVideoSource::retrieve() {
 }
 
 void StereoVideoSource::swap() {
-	auto tmp = frames_[0];
-	frames_[0] = frames_[1];
-	frames_[1] = tmp;
+	auto tmp = std::move(frames_[0]);
+	frames_[0] = std::move(frames_[1]);
+	frames_[1] = std::move(tmp);
 }
 
 bool StereoVideoSource::compute(int n, int b) {
 	auto &frame = frames_[1];
-	auto &left = frame.getChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanLeft);
-	auto &right = frame.getChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanRight);
+	auto &left = frame.get<cv::cuda::GpuMat>(Channel::Left);
+	auto &right = frame.get<cv::cuda::GpuMat>(Channel::Right);
 
-	const ftl::rgbd::channel_t chan = host_->getChannel();
+	const ftl::rgbd::Channel chan = host_->getChannel();
 	if (left.empty() || right.empty()) return false;
 
-	if (chan == ftl::rgbd::kChanDepth) {
+	if (chan == Channel::Depth) {
 		disp_->compute(frame, stream_);
 		
-		auto &disp = frame.getChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanDisparity);
-		auto &depth = frame.setChannel<cv::cuda::GpuMat>(ftl::rgbd::kChanDepth);
+		auto &disp = frame.get<cv::cuda::GpuMat>(Channel::Disparity);
+		auto &depth = frame.create<cv::cuda::GpuMat>(Channel::Depth);
 		if (depth.empty()) depth = cv::cuda::GpuMat(left.size(), CV_32FC1);
 
 		ftl::cuda::disparity_to_depth(disp, depth, params_, stream_);
 		
 		left.download(rgb_, stream_);
 		depth.download(depth_, stream_);
+		//frame.download(Channel::Left + Channel::Depth);
 		stream_.waitForCompletion();  // TODO:(Nick) Move to getFrames
-	} else if (chan == ftl::rgbd::kChanRight) {
+	} else if (chan == Channel::Right) {
 		left.download(rgb_, stream_);
 		right.download(depth_, stream_);
 		stream_.waitForCompletion();  // TODO:(Nick) Move to getFrames
diff --git a/components/rgbd-sources/src/stereovideo.hpp b/components/rgbd-sources/src/stereovideo.hpp
index 9fe3ca529f2f32300cb85aa47bd958b78f78984c..9d3325e1ac27ec544abeb409149cb89817dc29d2 100644
--- a/components/rgbd-sources/src/stereovideo.hpp
+++ b/components/rgbd-sources/src/stereovideo.hpp
@@ -31,7 +31,7 @@ class StereoVideoSource : public detail::Source {
 	bool retrieve();
 	bool compute(int n, int b);
 	bool isReady();
-	Camera parameters(channel_t chan);
+	Camera parameters(ftl::rgbd::Channel chan);
 
 	//const cv::Mat &getRight() const { return right_; }
 
diff --git a/components/rgbd-sources/src/streamer.cpp b/components/rgbd-sources/src/streamer.cpp
index c2676ac6a07b2c47914da9affffde5823d0fb9ca..a1019cb8e6ff990ce8cca20afaf8d59cc40571c6 100644
--- a/components/rgbd-sources/src/streamer.cpp
+++ b/components/rgbd-sources/src/streamer.cpp
@@ -17,6 +17,7 @@ using ftl::rgbd::detail::StreamClient;
 using ftl::rgbd::detail::ABRController;
 using ftl::codecs::definition_t;
 using ftl::codecs::device_t;
+using ftl::rgbd::Channel;
 using ftl::net::Universe;
 using std::string;
 using std::list;
@@ -50,7 +51,7 @@ Streamer::Streamer(nlohmann::json &config, Universe *net)
 
 	compress_level_ = value("compression", 1);
 	
-	net->bind("find_stream", [this](const std::string &uri) -> optional<UUID> {
+	net->bind("find_stream", [this](const std::string &uri) -> optional<ftl::UUID> {
 		SHARED_LOCK(mutex_,slk);
 
 		if (sources_.find(uri) != sources_.end()) {
@@ -91,7 +92,7 @@ Streamer::Streamer(nlohmann::json &config, Universe *net)
 	});
 
 	// Allow remote users to access camera calibration matrix
-	net->bind("source_details", [this](const std::string &uri, ftl::rgbd::channel_t chan) -> tuple<unsigned int,vector<unsigned char>> {
+	net->bind("source_details", [this](const std::string &uri, ftl::rgbd::Channel chan) -> tuple<unsigned int,vector<unsigned char>> {
 		vector<unsigned char> buf;
 		SHARED_LOCK(mutex_,slk);
 
@@ -110,11 +111,11 @@ Streamer::Streamer(nlohmann::json &config, Universe *net)
 		_addClient(source, N, rate, peer, dest);
 	});
 
-	net->bind("set_channel", [this](const string &uri, unsigned int chan) {
+	net->bind("set_channel", [this](const string &uri, Channel chan) {
 		SHARED_LOCK(mutex_,slk);
 
 		if (sources_.find(uri) != sources_.end()) {
-			sources_[uri]->src->setChannel((ftl::rgbd::channel_t)chan);
+			sources_[uri]->src->setChannel(chan);
 		}
 	});
 
@@ -366,9 +367,9 @@ void Streamer::_process(ftl::rgbd::FrameSet &fs) {
 		if (!fs.sources[j]->isReady()) continue;
 		if (src->clientCount == 0) continue;
 		//if (fs.channel1[j].empty() || (fs.sources[j]->getChannel() != ftl::rgbd::kChanNone && fs.channel2[j].empty())) continue;
-		if (!fs.frames[j].hasChannel(ftl::rgbd::kChanColour) || !fs.frames[j].hasChannel(fs.sources[j]->getChannel())) continue;
+		if (!fs.frames[j].hasChannel(Channel::Colour) || !fs.frames[j].hasChannel(fs.sources[j]->getChannel())) continue;
 
-		bool hasChan2 = fs.sources[j]->getChannel() != ftl::rgbd::kChanNone;
+		bool hasChan2 = fs.sources[j]->getChannel() != Channel::None;
 
 		totalclients += src->clientCount;
 
@@ -388,14 +389,14 @@ void Streamer::_process(ftl::rgbd::FrameSet &fs) {
 				// Receiver only waits for channel 1 by default
 				// TODO: Each encode could be done in own thread
 				if (hasChan2) {
-					enc2->encode(fs.frames[j].getChannel<cv::Mat>(fs.sources[j]->getChannel()), src->hq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
+					enc2->encode(fs.frames[j].get<cv::Mat>(fs.sources[j]->getChannel()), src->hq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
 						_transmitPacket(src, blk, 1, hasChan2, true);
 					});
 				} else {
 					if (enc2) enc2->reset();
 				}
 
-				enc1->encode(fs.frames[j].getChannel<cv::Mat>(ftl::rgbd::kChanColour), src->hq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
+				enc1->encode(fs.frames[j].get<cv::Mat>(Channel::Colour), src->hq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
 					_transmitPacket(src, blk, 0, hasChan2, true);
 				});
 			}
@@ -416,14 +417,14 @@ void Streamer::_process(ftl::rgbd::FrameSet &fs) {
 				// Important to send channel 2 first if needed...
 				// Receiver only waits for channel 1 by default
 				if (hasChan2) {
-					enc2->encode(fs.frames[j].getChannel<cv::Mat>(fs.sources[j]->getChannel()), src->lq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
+					enc2->encode(fs.frames[j].get<cv::Mat>(fs.sources[j]->getChannel()), src->lq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
 						_transmitPacket(src, blk, 1, hasChan2, false);
 					});
 				} else {
 					if (enc2) enc2->reset();
 				}
 
-				enc1->encode(fs.frames[j].getChannel<cv::Mat>(ftl::rgbd::kChanColour), src->lq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
+				enc1->encode(fs.frames[j].get<cv::Mat>(Channel::Colour), src->lq_bitrate, [this,src,hasChan2](const ftl::codecs::Packet &blk){
 					_transmitPacket(src, blk, 0, hasChan2, false);
 				});
 			}
diff --git a/components/rgbd-sources/test/CMakeLists.txt b/components/rgbd-sources/test/CMakeLists.txt
index 96e1441c5da6134eb17070d77e5ce9dff3a355f1..78bb6cec7e8c411ffbfe982a1b65320f56439bd5 100644
--- a/components/rgbd-sources/test/CMakeLists.txt
+++ b/components/rgbd-sources/test/CMakeLists.txt
@@ -5,6 +5,29 @@ add_executable(source_unit
 )
 target_include_directories(source_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
 target_link_libraries(source_unit
-	ftlcommon Eigen3::Eigen ${CUDA_LIBRARIES})
+	ftlcommon ftlcodecs ftlnet Eigen3::Eigen ${CUDA_LIBRARIES})
 
 add_test(SourceUnitTest source_unit)
+
+### Channel Unit ###############################################################
+add_executable(channel_unit
+	./tests.cpp
+	./channel_unit.cpp
+)
+target_include_directories(channel_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
+target_link_libraries(channel_unit
+	ftlcommon)
+
+add_test(ChannelUnitTest channel_unit)
+
+### Frame Unit #################################################################
+add_executable(frame_unit
+	./tests.cpp
+	./frame_unit.cpp
+	../src/frame.cpp
+)
+target_include_directories(frame_unit PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/../include")
+target_link_libraries(frame_unit
+	ftlcommon ftlcodecs)
+
+add_test(FrameUnitTest frame_unit)
diff --git a/components/rgbd-sources/test/channel_unit.cpp b/components/rgbd-sources/test/channel_unit.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..eb88777bd4a8c564c9a57d5fd99b53cdc164d67c
--- /dev/null
+++ b/components/rgbd-sources/test/channel_unit.cpp
@@ -0,0 +1,88 @@
+#include "catch.hpp"
+#include <ftl/rgbd/channels.hpp>
+
+using ftl::rgbd::Channel;
+using ftl::rgbd::Channels;
+
+TEST_CASE("channel casting", "") {
+	SECTION("cast channel to channels") {
+		Channels cs(Channel::Depth);
+
+        REQUIRE( (unsigned int)cs > 0 );
+        REQUIRE( cs.count() == 1 );
+	}
+
+    SECTION("cast channels to channel") {
+		Channels cs(Channel::Depth);
+        Channel c = (Channel)cs;
+
+        REQUIRE( c == Channel::Depth );
+	}
+}
+
+TEST_CASE("Channel or-ing", "") {
+	SECTION("Add channel to channel mask") {
+		Channels cs(Channel::Depth);
+
+        cs |= Channel::Right;
+
+        REQUIRE( cs.count() == 2 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Depth) );
+	}
+
+    SECTION("Combine multiple channels in assignment") {
+		Channels cs;
+
+        cs = Channel::Right | Channel::Flow | Channel::Left;
+
+        REQUIRE( cs.count() == 3 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Flow) );
+        REQUIRE( cs.has(Channel::Left) );
+	}
+
+    SECTION("Combine multiple channels at init") {
+		Channels cs = Channel::Right | Channel::Flow | Channel::Left;
+
+        REQUIRE( cs.count() == 3 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Flow) );
+        REQUIRE( cs.has(Channel::Left) );
+	}
+}
+
+TEST_CASE("Channel adding", "") {
+	SECTION("Add channel to channel mask") {
+		Channels cs(Channel::Depth);
+
+        cs += Channel::Right;
+
+        REQUIRE( cs.count() == 2 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Depth) );
+	}
+
+    SECTION("Combine multiple channels in assignment") {
+		Channels cs;
+
+        cs = Channel::Right + Channel::Flow + Channel::Left;
+
+        REQUIRE( cs.count() == 3 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Flow) );
+        REQUIRE( cs.has(Channel::Left) );
+	}
+}
+
+TEST_CASE("Channel subtracting", "") {
+	SECTION("Remove channel from channel mask") {
+		Channels cs = Channel::Right | Channel::Flow | Channel::Left;
+
+        cs -= Channel::Flow;
+
+        REQUIRE( cs.count() == 2 );
+        REQUIRE( cs.has(Channel::Right) );
+        REQUIRE( cs.has(Channel::Left) );
+	}
+}
diff --git a/components/rgbd-sources/test/frame_unit.cpp b/components/rgbd-sources/test/frame_unit.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..9f3c5b33eb450087959bb560f6c7ea15732a0581
--- /dev/null
+++ b/components/rgbd-sources/test/frame_unit.cpp
@@ -0,0 +1,269 @@
+#include "catch.hpp"
+#include <ftl/rgbd/frame.hpp>
+
+using ftl::rgbd::Frame;
+using ftl::rgbd::Channel;
+using ftl::rgbd::Format;
+
+TEST_CASE("Frame::create() cpu mat", "") {
+	SECTION("in empty channel with format") {
+		Frame f;
+		auto &m = f.create<cv::Mat>(Channel::Colour, Format<float4>(200,200));
+
+		REQUIRE( m.type() == CV_32FC4 );
+		REQUIRE( m.cols == 200 );
+		REQUIRE( m.rows == 200 );
+	}
+
+	SECTION("in non-empty channel with format") {
+		Frame f;
+		f.create<cv::Mat>(Channel::Colour, Format<float>(200,100));
+		auto &m = f.create<cv::Mat>(Channel::Colour, Format<float4>(200,200));
+
+		REQUIRE( m.type() == CV_32FC4 );
+		REQUIRE( m.cols == 200 );
+		REQUIRE( m.rows == 200 );
+	}
+}
+
+TEST_CASE("Frame::get()", "") {
+	SECTION("get a non-existant host channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &m = f.get<cv::Mat>(Channel::Colour);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("get a non-existant gpu channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &m = f.get<cv::cuda::GpuMat>(Channel::Colour);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("get a valid host channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::Mat>(Channel::Colour, Format<uchar3>(1024,1024));
+			auto &m = f.get<cv::Mat>(Channel::Colour);
+
+			REQUIRE( m.type() == CV_8UC3 );
+			REQUIRE( m.cols == 1024 );
+			REQUIRE( m.rows == 1024 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+
+	SECTION("get a valid gpu channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::cuda::GpuMat>(Channel::Colour, Format<uchar3>(1024,1024));
+			auto &m = f.get<cv::cuda::GpuMat>(Channel::Colour);
+
+			REQUIRE( m.type() == CV_8UC3 );
+			REQUIRE( m.cols == 1024 );
+			REQUIRE( m.rows == 1024 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+
+	SECTION("get a cpu mat from gpu channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::cuda::GpuMat>(Channel::Colour, Format<uchar3>(1024,1024));
+			REQUIRE( f.isGPU(Channel::Colour) );
+
+			auto &m = f.get<cv::Mat>(Channel::Colour);
+
+			REQUIRE( f.isCPU(Channel::Colour) );
+			REQUIRE( m.type() == CV_8UC3 );
+			REQUIRE( m.cols == 1024 );
+			REQUIRE( m.rows == 1024 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+
+	SECTION("get a gpu mat from cpu channel") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::Mat>(Channel::Colour, Format<uchar3>(1024,1024));
+			REQUIRE( f.isCPU(Channel::Colour) );
+			
+			auto &m = f.get<cv::cuda::GpuMat>(Channel::Colour);
+
+			REQUIRE( f.isGPU(Channel::Colour) );
+			REQUIRE( m.type() == CV_8UC3 );
+			REQUIRE( m.cols == 1024 );
+			REQUIRE( m.rows == 1024 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+}
+
+TEST_CASE("Frame::createTexture()", "") {
+	SECTION("Missing format and no existing mat") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &t = f.createTexture<float>(Channel::Depth);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("Missing format but with existing host mat") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::Mat>(Channel::Depth, Format<float>(100,100));
+			auto &t = f.createTexture<float>(Channel::Depth);
+
+			REQUIRE( t.width() == 100 );
+			REQUIRE( t.cvType() == CV_32FC1 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+
+	SECTION("Missing format but with incorrect existing host mat") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.create<cv::Mat>(Channel::Depth, Format<uchar4>(100,100));
+			auto &t = f.createTexture<float>(Channel::Depth);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("With format and no existing mat") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &t = f.createTexture<float>(Channel::Depth, Format<float>(1024,1024));
+			REQUIRE( t.cvType() == CV_32FC1 );
+			REQUIRE( t.cudaTexture() > 0 );
+			REQUIRE( t.devicePtr() != nullptr );
+
+			auto &m = f.get<cv::cuda::GpuMat>(Channel::Depth);
+			REQUIRE( m.data == reinterpret_cast<uchar*>(t.devicePtr()) );
+			REQUIRE( m.type() == CV_32FC1 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+
+	SECTION("Unchanged type is same texture object") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &t = f.createTexture<float>(Channel::Depth, Format<float>(1024,1024));
+			REQUIRE( t.cvType() == CV_32FC1 );
+			
+			auto tex = t.cudaTexture();
+			float *ptr = t.devicePtr();
+
+			REQUIRE( ptr != nullptr );
+
+			auto &t2 = f.createTexture<float>(Channel::Depth, Format<float>(1024,1024));
+
+			REQUIRE( tex == t2.cudaTexture() );
+			REQUIRE( ptr == t2.devicePtr() );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+}
+
+TEST_CASE("Frame::getTexture()", "") {
+	SECTION("Missing texture") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			auto &t = f.getTexture<float>(Channel::Depth);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("Texture of incorrect type") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.createTexture<uchar4>(Channel::Depth, Format<uchar4>(100,100));
+			auto &t = f.getTexture<float>(Channel::Depth);
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( hadexception );
+	}
+
+	SECTION("Valid texture get") {
+		Frame f;
+		bool hadexception = false;
+
+		try {
+			f.createTexture<uchar4>(Channel::Colour, Format<uchar4>(100,100));
+			auto &t = f.getTexture<uchar4>(Channel::Colour);
+
+			REQUIRE( t.cvType() == CV_8UC4 );
+			REQUIRE( t.width() == 100 );
+		} catch (ftl::exception &e) {
+			hadexception = true;
+		}
+
+		REQUIRE( !hadexception );
+	}
+}