diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp
index 15e9ce2653ca136354b4dd803320ea80ec235d5d..8895db1b2322eff090fb4bbb8523438c715b03d1 100644
--- a/applications/gui/src/camera.cpp
+++ b/applications/gui/src/camera.cpp
@@ -10,6 +10,7 @@
 
 #include <ftl/operators/antialiasing.hpp>
 #include <ftl/cuda/normals.hpp>
+#include <ftl/render/colouriser.hpp>
 
 #include <ftl/codecs/faces.hpp>
 
@@ -72,29 +73,13 @@ ftl::gui::Camera::Camera(ftl::gui::Screen *screen, int fsmask, int fid, ftl::cod
 	//posewin_->setVisible(false);
 	posewin_ = nullptr;
 	renderer_ = nullptr;
+	renderer2_ = nullptr;
 	post_pipe_ = nullptr;
 	record_stream_ = nullptr;
 	transform_ix_ = -1;
+	stereo_ = false;
 
-	/*src->setCallback([this](int64_t ts, ftl::rgbd::Frame &frame) {
-		UNIQUE_LOCK(mutex_, lk);
-
-		auto &channel1 = frame.get<GpuMat>(Channel::Colour);
-		im1_.create(channel1.size(), channel1.type());
-		channel1.download(im1_);
-
-		// OpenGL (0,0) bottom left
-		cv::flip(im1_, im1_, 0);
-
-		if (channel_ != Channel::Colour && channel_ != Channel::None && frame.hasChannel(channel_)) {
-			auto &channel2 = frame.get<GpuMat>(channel_);
-			im2_.create(channel2.size(), channel2.type());
-			channel2.download(im2_);
-			cv::flip(im2_, im2_, 0);
-		}
-	});*/
-
-	//auto *host = screen->root();
+	colouriser_ = ftl::create<ftl::render::Colouriser>(screen->root(), "colouriser");
 
 	// Is virtual camera?
 	if (fid == 255) {
@@ -120,90 +105,6 @@ ftl::gui::Camera::Camera(ftl::gui::Screen *screen, int fsmask, int fid, ftl::cod
 	}
 }
 
-/*template<class T>
-static Eigen::Matrix<T,4,4> lookAt
-(
-    Eigen::Matrix<T,3,1> const & eye,
-    Eigen::Matrix<T,3,1> const & center,
-    Eigen::Matrix<T,3,1> const & up
-)
-{
-    typedef Eigen::Matrix<T,4,4> Matrix4;
-    typedef Eigen::Matrix<T,3,1> Vector3;
-
-    Vector3 f = (center - eye).normalized();
-    Vector3 u = up.normalized();
-    Vector3 s = f.cross(u).normalized();
-    u = s.cross(f);
-
-    Matrix4 res;
-    res <<  s.x(),s.y(),s.z(),-s.dot(eye),
-            u.x(),u.y(),u.z(),-u.dot(eye),
-            -f.x(),-f.y(),-f.z(),f.dot(eye),
-            0,0,0,1;
-
-    return res;
-}*/
-
-/*static float4 screenProjection(
-		const Eigen::Vector3f &pa,  // Screen corner 1
-		const Eigen::Vector3f &pb,  // Screen corner 2
-		const Eigen::Vector3f &pc,  // Screen corner 3
-		const Eigen::Vector3f &pe  // Eye position
-		) {
-
-    Eigen::Vector3f va, vb, vc;
-    Eigen::Vector3f vr, vu, vn;
-
-    float l, r, b, t, d;
-
-    // Compute an orthonormal basis for the screen.
-
-    //subtract(vr, pb, pa);
-    //subtract(vu, pc, pa);
-	vr = pb - pa;
-	vu = pc - pa;
-
-    //normalize(vr);
-    //normalize(vu);
-    //cross_product(vn, vr, vu);
-    //normalize(vn);
-	vr.normalize();
-	vu.normalize();
-	vn = vr.cross(vu);
-	vn.normalize();
-
-    // Compute the screen corner vectors.
-
-    //subtract(va, pa, pe);
-    //subtract(vb, pb, pe);
-    //subtract(vc, pc, pe);
-	va = pa - pe;
-	vb = pb - pe;
-	vc = pc - pe;
-
-    // Find the distance from the eye to screen plane.
-
-    //d = -dot_product(va, vn);
-	d = -va.dot(vn);
-
-    // Find the extent of the perpendicular projection.
-
-    //l = dot_product(vr, va) * n / d;
-    //r = dot_product(vr, vb) * n / d;
-    //b = dot_product(vu, va) * n / d;
-    //t = dot_product(vu, vc) * n / d;
-
-	float n = d;
-	l = vr.dot(va) * n / d;
-	r = vr.dot(vb) * n / d;
-	b = vu.dot(va) * n / d;
-	t = vu.dot(vc) * n / d;
-
-	//return nanogui::frustum(l,r,b,t,n,f);
-	return make_float4(l,r,b,t);
-}*/
-
 ftl::gui::Camera::~Camera() {
 	//delete writer_;
 	//delete fileout_;
@@ -335,23 +236,50 @@ void ftl::gui::Camera::draw(std::vector<ftl::rgbd::FrameSet*> &fss) {
 	}
 }
 
+void ftl::gui::Camera::setStereo(bool v) {
+	UNIQUE_LOCK(mutex_, lk);
+
+	if (isVirtual()) {
+		stereo_ = v;
+	} else if (v && availableChannels().has(Channel::Right)) {
+		stereo_ = true;
+	} else {
+		stereo_ = false;
+	}
+}
+
 void ftl::gui::Camera::_draw(std::vector<ftl::rgbd::FrameSet*> &fss) {
 	frame_.reset();
 	frame_.setOrigin(&state_);
 
 	{
 		FTL_Profile("Render",0.034);
-		renderer_->begin(frame_);
-		for (auto *fs : fss) {
-			if (!usesFrameset(fs->id)) continue;
+		renderer_->begin(frame_, Channel::Colour);
+		if (isStereo()) {
+			if (!renderer2_) {
+				renderer2_ = ftl::create<ftl::render::CUDARender>(screen_->root(), std::string("vcam")+std::to_string(vcamcount++));
+			}
+			renderer2_->begin(frame_, Channel::Colour2);
+		}
 
-			// FIXME: Should perhaps remain locked until after end is called?
-			// Definitely: causes flashing if not.
-			//UNIQUE_LOCK(fs->mtx,lk);
-			fs->mtx.lock();
-			renderer_->submit(fs, Channels<0>(channel_), transforms_[fs->id]);
+		try {
+			for (auto *fs : fss) {
+				if (!usesFrameset(fs->id)) continue;
+
+				fs->mtx.lock();
+				renderer_->submit(fs, ftl::codecs::Channels<0>(Channel::Colour), transforms_[fs->id]);
+				if (isStereo()) renderer2_->submit(fs, ftl::codecs::Channels<0>(Channel::Colour), transforms_[fs->id]);
+			}
+
+			if (channel_ != Channel::Left && channel_ != Channel::Right && channel_ != Channel::None) {
+				renderer_->blend(0.5f, channel_);
+			}
+
+			renderer_->end();
+			if (isStereo()) renderer2_->end();
+		} catch(std::exception &e) {
+			LOG(ERROR) << "Exception in render: " << e.what();
 		}
-		renderer_->end();
 		for (auto *fs : fss) {
 			fs->mtx.unlock();
 		}
@@ -364,8 +292,13 @@ void ftl::gui::Camera::_draw(std::vector<ftl::rgbd::FrameSet*> &fss) {
 
 	post_pipe_->apply(frame_, frame_, 0);
 
-	channels_ = frame_.getChannels() + Channel::Right + Channel::ColourNormals;
-	_downloadFrames(&frame_);
+	channels_ = frame_.getChannels();
+
+	if (isStereo()) {
+		_downloadFrames(frame_.getTexture<uchar4>(Channel::Colour), frame_.getTexture<uchar4>(Channel::Colour2));
+	} else {
+		_downloadFrame(frame_.getTexture<uchar4>(Channel::Colour));
+	}
 
 	if (screen_->root()->value("show_poses", false)) {
 		cv::Mat over_col, over_depth;
@@ -402,15 +335,9 @@ void ftl::gui::Camera::_draw(std::vector<ftl::rgbd::FrameSet*> &fss) {
 	}
 }
 
-void ftl::gui::Camera::_downloadFrames(ftl::rgbd::Frame *frame) {
-	if (!frame) return;
-
-	// Use high res colour if available..
-	auto &channel1 = (frame->hasChannel(Channel::ColourHighRes)) ? 
-			frame->get<GpuMat>(Channel::ColourHighRes) :
-			frame->get<GpuMat>(Channel::Colour);
-	im1_.create(channel1.size(), channel1.type());
-	channel1.download(im1_);
+void ftl::gui::Camera::_downloadFrames(ftl::cuda::TextureObject<uchar4> &a, ftl::cuda::TextureObject<uchar4> &b) {
+	im1_.create(cv::Size(a.width(), a.height()), CV_8UC4);
+	a.to_gpumat().download(im1_);
 
 	// OpenGL (0,0) bottom left
 	cv::flip(im1_, im1_, 0);
@@ -418,39 +345,33 @@ void ftl::gui::Camera::_downloadFrames(ftl::rgbd::Frame *frame) {
 	width_ = im1_.cols;
 	height_ = im1_.rows;
 
-	if (channel_ != Channel::Colour && channel_ != Channel::None && frame->hasChannel(channel_)) {
-		auto &channel2 = frame->get<GpuMat>(channel_);
-		im2_.create(channel2.size(), channel2.type());
-		channel2.download(im2_);
-		//LOG(INFO) << "Have channel2: " << im2_.type() << ", " << im2_.size();
-		cv::flip(im2_, im2_, 0);
-	} else if (channel_ == Channel::ColourNormals && frame->hasChannel(Channel::Depth)) {
-		// We can calculate normals here.
-		ftl::cuda::normals(
-			frame->createTexture<half4>(Channel::Normals, ftl::rgbd::Format<half4>(frame->get<cv::cuda::GpuMat>(Channel::Depth).size())),
-			frame->createTexture<float>(Channel::Depth),
-			frame->getLeftCamera(), 0
-		);
-
-		frame->create<GpuMat>(Channel::ColourNormals, ftl::rgbd::Format<uchar4>(frame->get<cv::cuda::GpuMat>(Channel::Depth).size())).setTo(cv::Scalar(0,0,0,0), cv::cuda::Stream::Null());
-
-		ftl::cuda::normal_visualise(frame->getTexture<half4>(Channel::Normals), frame->createTexture<uchar4>(Channel::ColourNormals),
-				make_float3(0.3f,0.3f,0.3f),
-				make_uchar4(200,200,200,255),
-				make_uchar4(50,50,50,255), 0);
-
-		auto &channel2 = frame->get<GpuMat>(Channel::ColourNormals);
-		im2_.create(channel2.size(), channel2.type());
-		channel2.download(im2_);
-		cv::flip(im2_, im2_, 0);
+	im2_.create(cv::Size(b.width(), b.height()), CV_8UC4);
+	b.to_gpumat().download(im2_);
+	cv::flip(im2_, im2_, 0);
+
+	if (im2_.cols != im1_.cols || im2_.rows != im1_.rows) {
+		throw FTL_Error("Left and right images are different sizes");
 	}
 }
 
+void ftl::gui::Camera::_downloadFrame(ftl::cuda::TextureObject<uchar4> &a) {
+	im1_.create(cv::Size(a.width(), a.height()), CV_8UC4);
+	a.to_gpumat().download(im1_);
+
+	// OpenGL (0,0) bottom left
+	cv::flip(im1_, im1_, 0);
+
+	width_ = im1_.cols;
+	height_ = im1_.rows;
+
+	im2_ = cv::Mat();
+}
+
 void ftl::gui::Camera::update(int fsid, const ftl::codecs::Channels<0> &c) {
 	if (!isVirtual() && ((1 << fsid) & fsmask_)) {
 		channels_ = c;
 		if (c.has(Channel::Depth)) {
-			channels_ += Channel::ColourNormals;
+			//channels_ += Channel::ColourNormals;
 		}
 	}
 }
@@ -474,7 +395,14 @@ void ftl::gui::Camera::update(std::vector<ftl::rgbd::FrameSet*> &fss) {
 
 			if ((size_t)fid_ >= fs->frames.size()) return;
 			frame = &fs->frames[fid_];
-			_downloadFrames(frame);
+
+			auto &buf = colouriser_->colourise(*frame, channel_, 0);
+			if (isStereo() && frame->hasChannel(Channel::Right)) {
+				_downloadFrames(buf, frame->createTexture<uchar4>(Channel::Right));
+			} else {
+				_downloadFrame(buf);
+			}
+
 			auto n = frame->get<std::string>("name");
 			if (n) {
 				name_ = *n;
@@ -561,7 +489,6 @@ void ftl::gui::Camera::showSettings() {
 
 #ifdef HAVE_OPENVR
 bool ftl::gui::Camera::setVR(bool on) {
-	
 	if (on == vr_mode_) {
 		LOG(WARNING) << "VR mode already enabled";
 		return on;
@@ -569,17 +496,23 @@ bool ftl::gui::Camera::setVR(bool on) {
 	vr_mode_ = on;
 
 	if (on) {
-		setChannel(Channel::Right);
+		setStereo(true);
+
+		UNIQUE_LOCK(mutex_, lk);
 		//src_->set("baseline", baseline_);
 		state_.getLeft().baseline = baseline_;
 
 		Eigen::Matrix3d intrinsic;
+
+		unsigned int size_x, size_y;
+		screen_->getVR()->GetRecommendedRenderTargetSize(&size_x, &size_y);
+		state_.getLeft().width = size_x;
+		state_.getLeft().height = size_y;
+		state_.getRight().width = size_x;
+		state_.getRight().height = size_y;
 		
 		intrinsic = getCameraMatrix(screen_->getVR(), vr::Eye_Left);
 		CHECK(intrinsic(0, 2) < 0 && intrinsic(1, 2) < 0);
-		//src_->set("focal", intrinsic(0, 0));
-		//src_->set("centre_x", intrinsic(0, 2));
-		//src_->set("centre_y", intrinsic(1, 2));
 		state_.getLeft().fx = intrinsic(0,0);
 		state_.getLeft().fy = intrinsic(0,0);
 		state_.getLeft().cx = intrinsic(0,2);
@@ -587,9 +520,6 @@ bool ftl::gui::Camera::setVR(bool on) {
 		
 		intrinsic = getCameraMatrix(screen_->getVR(), vr::Eye_Right);
 		CHECK(intrinsic(0, 2) < 0 && intrinsic(1, 2) < 0);
-		//src_->set("focal_right", intrinsic(0, 0));
-		//src_->set("centre_x_right", intrinsic(0, 2));
-		//src_->set("centre_y_right", intrinsic(1, 2));
 		state_.getRight().fx = intrinsic(0,0);
 		state_.getRight().fy = intrinsic(0,0);
 		state_.getRight().cx = intrinsic(0,2);
@@ -599,8 +529,11 @@ bool ftl::gui::Camera::setVR(bool on) {
 	}
 	else {
 		vr_mode_ = false;
-		setChannel(Channel::Left); // reset to left channel
-		// todo restore camera params<
+		setStereo(false);
+
+		UNIQUE_LOCK(mutex_, lk);
+		state_.getLeft() = ftl::rgbd::Camera::from(intrinsics_);
+		state_.getRight() = state_.getLeft();
 	}
 
 	return vr_mode_;
@@ -608,60 +541,11 @@ bool ftl::gui::Camera::setVR(bool on) {
 #endif
 
 void ftl::gui::Camera::setChannel(Channel c) {
-#ifdef HAVE_OPENVR
-	if (isVR() && (c != Channel::Right)) {
-		LOG(ERROR) << "Changing channel in VR mode is not possible.";
-		return;
-	}
-#endif
-
+	UNIQUE_LOCK(mutex_, lk);
 	channel_ = c;
 }
 
-static void visualizeDepthMap(	const cv::Mat &depth, cv::Mat &out,
-								const float max_depth)
-{
-	DCHECK(max_depth > 0.0);
-
-	depth.convertTo(out, CV_8U, 255.0f / max_depth);
-	out = 255 - out;
-	cv::Mat mask = (depth >= 39.0f); // TODO (mask for invalid pixels)
-	
-	applyColorMap(out, out, cv::COLORMAP_JET);
-	out.setTo(cv::Scalar(255, 255, 255), mask);
-	cv::cvtColor(out,out, cv::COLOR_BGR2BGRA);
-}
-
-static void visualizeEnergy(	const cv::Mat &depth, cv::Mat &out,
-								const float max_depth)
-{
-	DCHECK(max_depth > 0.0);
-
-	depth.convertTo(out, CV_8U, 255.0f / max_depth);
-	//out = 255 - out;
-	//cv::Mat mask = (depth >= 39.0f); // TODO (mask for invalid pixels)
-	
-	applyColorMap(out, out, cv::COLORMAP_JET);
-	//out.setTo(cv::Scalar(255, 255, 255), mask);
-	cv::cvtColor(out,out, cv::COLOR_BGR2BGRA);
-}
-
-static void visualizeWeights(const cv::Mat &weights, cv::Mat &out)
-{
-	weights.convertTo(out, CV_8U, 255.0f / 32767.0f);
-	//out = 255 - out;
-	//cv::Mat mask = (depth >= 39.0f); // TODO (mask for invalid pixels)
-	
-#if (OPENCV_VERSION >= 40102)
-	applyColorMap(out, out, cv::COLORMAP_TURBO);
-#else
-	applyColorMap(out, out, cv::COLORMAP_JET);
-#endif
-	//out.setTo(cv::Scalar(255, 255, 255), mask);
-	cv::cvtColor(out,out, cv::COLOR_BGR2BGRA);
-}
-
-static void drawEdges(	const cv::Mat &in, cv::Mat &out,
+/*static void drawEdges(	const cv::Mat &in, cv::Mat &out,
 						const int ksize = 3, double weight = -1.0, const int threshold = 32,
 						const int threshold_type = cv::THRESH_TOZERO)
 {
@@ -671,38 +555,15 @@ static void drawEdges(	const cv::Mat &in, cv::Mat &out,
 
 	cv::Mat edges_color(in.size(), CV_8UC4);
 	cv::addWeighted(edges, weight, out, 1.0, 0.0, out, CV_8UC4);
-}
-
-cv::Mat ftl::gui::Camera::visualizeActiveChannel() {
-	cv::Mat result;
-	switch(channel_) {
-		case Channel::Smoothing:
-		case Channel::Confidence:
-			visualizeEnergy(im2_, result, 1.0);
-			break;
-		case Channel::Density:
-		case Channel::Energy:
-			visualizeEnergy(im2_, result, 10.0);
-			break;
-		case Channel::Depth:
-			visualizeDepthMap(im2_, result, 7.0);
-			if (screen_->root()->value("showEdgesInDepth", false)) drawEdges(im1_, result);
-			break;
-		case Channel::ColourNormals:
-		case Channel::Right:
-			result = im2_;
-			break;
-		default: break;
-	}
-	return result;
-}
+}*/
 
 bool ftl::gui::Camera::thumbnail(cv::Mat &thumb) {
-	UNIQUE_LOCK(mutex_, lk);
-	/*src_->grab(1,9);*/
-	cv::Mat sel = (channel_ != Channel::None && channel_ != Channel::Colour && !im2_.empty()) ? visualizeActiveChannel() : im1_;
-	if (sel.empty()) return false;
-	cv::resize(sel, thumb, cv::Size(320,180));
+	{
+		UNIQUE_LOCK(mutex_, lk);
+		if (im1_.empty()) return false;
+		// FIXME: Use correct aspect ratio?
+		cv::resize(im1_, thumb, cv::Size(320,180));
+	}
 	cv::flip(thumb, thumb, 0);
 	return true;
 }
@@ -731,7 +592,7 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 			
 			vr::VRCompositor()->WaitGetPoses(rTrackedDevicePose_, vr::k_unMaxTrackedDeviceCount, NULL, 0 );
 
-			if ((channel_ == Channel::Right) && rTrackedDevicePose_[vr::k_unTrackedDeviceIndex_Hmd].bPoseIsValid )
+			if (isStereo() && rTrackedDevicePose_[vr::k_unTrackedDeviceIndex_Hmd].bPoseIsValid )
 			{
 				Eigen::Matrix4d eye_l = ConvertSteamVRMatrixToMatrix4(
 					vr::VRSystem()->GetEyeToHeadTransform(vr::Eye_Left));
@@ -745,6 +606,7 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 					baseline_ = baseline_in;
 					//src_->set("baseline", baseline_);
 					state_.getLeft().baseline = baseline_;
+					state_.getRight().baseline = baseline_;
 				}
 				Eigen::Matrix4d pose = ConvertSteamVRMatrixToMatrix4(rTrackedDevicePose_[vr::k_unTrackedDeviceIndex_Hmd].mDeviceToAbsoluteTracking);
 				Eigen::Vector3d ea = pose.block<3, 3>(0, 0).eulerAngles(0, 1, 2);
@@ -782,105 +644,27 @@ const GLTexture &ftl::gui::Camera::captureFrame() {
 				transforms_[transform_ix_] = viewPose;
 			}
 		}
-	
-		//src_->grab();
-
-		// When switching from right to depth, client may still receive
-		// right images from previous batch (depth.channels() == 1 check)
-
-		/* todo: does not work
-		if (channel_ == Channel::Deviation &&
-			depth_.rows > 0 && depth_.channels() == 1)
-		{
-			if (!stats_) {
-				stats_ = new StatisticsImage(depth_.size());
-			}
-			
-			stats_->update(depth_);
-		}*/
 
 		cv::Mat tmp;
 
-		switch(channel_) {
-			case Channel::Smoothing:
-			case Channel::Confidence:
-				if (im2_.rows == 0) { break; }
-				visualizeEnergy(im2_, tmp, screen_->root()->value("float_image_max", 1.0f));
-				texture2_.update(tmp);
-				break;
-
-			case Channel::Weights:
-				if (im2_.rows == 0) { break; }
-				visualizeWeights(im2_, tmp);
-				texture2_.update(tmp);
-				break;
-			
-			case Channel::Density:
-			case Channel::Energy:
-				if (im2_.rows == 0) { break; }
-				visualizeEnergy(im2_, tmp, 10.0);
-				texture2_.update(tmp);
-				break;
-			
-			case Channel::Depth:
-				if (im2_.rows == 0 || im2_.type() != CV_32F) { break; }
-				visualizeDepthMap(im2_, tmp, 7.0);
-				if (screen_->root()->value("showEdgesInDepth", false)) drawEdges(im1_, tmp);
-				texture2_.update(tmp);
-				break;
-			
-			case Channel::Deviation:
-				if (im2_.rows == 0) { break; }/*
-				//imageSize = Vector2f(depth.cols, depth.rows);
-				stats_->getStdDev(tmp);
-				tmp.convertTo(tmp, CV_8U, 1000.0);
-				applyColorMap(tmp, tmp, cv::COLORMAP_HOT);
-				texture2_.update(tmp);*/
-				break;
-
-			//case Channel::Flow:
-			case Channel::ColourNormals:
-			case Channel::Right:
-					if (im2_.rows == 0 || im2_.type() != CV_8UC4) { break; }
-					texture2_.update(im2_);
-					break;
-
-			default:
-				break;
-				/*if (rgb_.rows == 0) { break; }
-				//imageSize = Vector2f(rgb.cols,rgb.rows);
-				texture_.update(rgb_);
-				#ifdef HAVE_OPENVR
-				if (screen_->hasVR() && depth_.channels() >= 3) {
-					LOG(INFO) << "DRAW RIGHT";
-					textureRight_.update(depth_);
-				}
-				#endif
-				*/
-		}
-
 		if (im1_.rows != 0) {
-			//imageSize = Vector2f(rgb.cols,rgb.rows);
 			texture1_.update(im1_);
 		}
+		if (isStereo() && im2_.rows != 0) {
+			texture2_.update(im2_);
+		}
 	}
 
 	return texture1_;
 }
 
 void ftl::gui::Camera::snapshot(const std::string &filename) {
-	UNIQUE_LOCK(mutex_, lk);
-	cv::Mat blended;
-	cv::Mat visualized = visualizeActiveChannel();
+	cv::Mat flipped;
 
-	if (!visualized.empty()) {
-		double alpha = screen_->root()->value("blending", 0.5);
-		cv::addWeighted(im1_, alpha, visualized, 1.0-alpha, 0, blended);
-	} else {
-		blended = im1_;
+	{
+		UNIQUE_LOCK(mutex_, lk);
+		cv::flip(im1_, flipped, 0);
 	}
-	cv::Mat flipped;
-	cv::flip(blended, flipped, 0);
 	cv::cvtColor(flipped, flipped, cv::COLOR_BGRA2BGR);
 	cv::imwrite(filename, flipped);
 }
diff --git a/applications/gui/src/camera.hpp b/applications/gui/src/camera.hpp
index 361ee439bb5d612a061d925e07d600f1c5da83c1..ce764be86f1252f693dbb74c9f5ca4f152de1a82 100644
--- a/applications/gui/src/camera.hpp
+++ b/applications/gui/src/camera.hpp
@@ -53,6 +53,9 @@ class Camera {
 	void isPaused();
 	inline bool isVirtual() const { return fid_ == 255; }
 	const ftl::codecs::Channels<0> &availableChannels() { return channels_; }
+	inline bool isStereo() const { return stereo_; }
+
+	void setStereo(bool v);
 
 	/**
 	 * Main function to obtain latest frames.
@@ -98,7 +101,6 @@ class Camera {
 #endif
 
 	private:
-	cv::Mat visualizeActiveChannel();
 
 	Screen *screen_;
 	unsigned int fsmask_;  // Frameset Mask
@@ -126,8 +128,12 @@ class Camera {
 	ftl::codecs::Channels<0> channels_;
 	cv::Mat im1_; // first channel (left)
 	cv::Mat im2_; // second channel ("right")
+	bool stereo_;
 
 	ftl::render::CUDARender *renderer_;
+	ftl::render::CUDARender *renderer2_;
+	ftl::render::Colouriser *colouriser_;
+
 	ftl::Configurable *intrinsics_;
 	ftl::operators::Graph *post_pipe_;
 	ftl::rgbd::Frame frame_;
@@ -148,7 +154,8 @@ class Camera {
 	float baseline_;
 	#endif
 
-	void _downloadFrames(ftl::rgbd::Frame *frame);
+	void _downloadFrames(ftl::cuda::TextureObject<uchar4> &, ftl::cuda::TextureObject<uchar4> &);
+	void _downloadFrame(ftl::cuda::TextureObject<uchar4> &);
 	void _draw(std::vector<ftl::rgbd::FrameSet*> &fss);
 };
 
diff --git a/applications/gui/src/media_panel.cpp b/applications/gui/src/media_panel.cpp
index 8723000a1f18019d8021590cbd46b81176fb9fdc..e93a4affe690d952e6feb342e4bdb52257684142 100644
--- a/applications/gui/src/media_panel.cpp
+++ b/applications/gui/src/media_panel.cpp
@@ -154,6 +154,20 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen, ftl::gui::SourceWindow *sourceW
 		channel_buttons_[i] = button;
 	}
 
+	auto *stereobut = new Button(popup, "Stereo On");
+	stereobut->setCallback([this,stereobut]() {
+		ftl::gui::Camera *cam = screen_->activeCamera();
+		if (cam) {
+			cam->setStereo(!cam->isStereo());
+			if (cam->isStereo()) {
+				stereobut->setCaption("Stereo Off");
+			} else {
+				stereobut->setCaption("Stereo On");
+			}
+		}
+	});
+	
+
 	auto *popbutton = new PopupButton(popup, "More");
 	popbutton->setSide(Popup::Side::Right);
 	popbutton->setChevronIcon(ENTYPO_ICON_CHEVRON_SMALL_RIGHT);
diff --git a/applications/gui/src/screen.cpp b/applications/gui/src/screen.cpp
index 2d2274058087c0f3b5bd1f6d6f876e798b3ed05b..39a9b65dcf18241fbf5745515dba711fd1875cb7 100644
--- a/applications/gui/src/screen.cpp
+++ b/applications/gui/src/screen.cpp
@@ -524,17 +524,20 @@ void ftl::gui::Screen::draw(NVGcontext *ctx) {
 		leftEye_ = mImageID;
 		rightEye_ = camera_->getRight().texture();
 
-		if (camera_->getChannel() != ftl::codecs::Channel::Left) { mImageID = rightEye_; }
+		//if (camera_->getChannel() != ftl::codecs::Channel::Left) { mImageID = rightEye_; }
 
 		#ifdef HAVE_OPENVR
 		if (isVR() && imageSize[0] > 0 && camera_->getLeft().isValid() && camera_->getRight().isValid()) {
 			
+			glBindTexture(GL_TEXTURE_2D, leftEye_);
 			vr::Texture_t leftEyeTexture = {(void*)(uintptr_t)leftEye_, vr::TextureType_OpenGL, vr::ColorSpace_Gamma };
 			vr::VRCompositor()->Submit(vr::Eye_Left, &leftEyeTexture );
 
 			glBindTexture(GL_TEXTURE_2D, rightEye_);
 			vr::Texture_t rightEyeTexture = {(void*)(uintptr_t)rightEye_, vr::TextureType_OpenGL, vr::ColorSpace_Gamma };
 			vr::VRCompositor()->Submit(vr::Eye_Right, &rightEyeTexture );
+
+			glFlush();
 			
 			mImageID = leftEye_;
 		}
@@ -556,10 +559,10 @@ void ftl::gui::Screen::draw(NVGcontext *ctx) {
 			glActiveTexture(GL_TEXTURE0);
 			glBindTexture(GL_TEXTURE_2D, leftEye_);
 			glActiveTexture(GL_TEXTURE1);
-			glBindTexture(GL_TEXTURE_2D, (camera_->getRight().isValid()) ? rightEye_ : leftEye_);
+			glBindTexture(GL_TEXTURE_2D, (camera_->isStereo() && camera_->getRight().isValid()) ? rightEye_ : leftEye_);
 			mShader.setUniform("image1", 0);
 			mShader.setUniform("image2", 1);
-			mShader.setUniform("blendAmount", (camera_->getChannel() != ftl::codecs::Channel::Left) ? root_->value("blending", 0.5f) : 1.0f);
+			mShader.setUniform("blendAmount", (camera_->isStereo()) ? root_->value("blending", 0.5f) : 1.0f);
 			mShader.setUniform("scaleFactor", scaleFactor);
 			mShader.setUniform("position", imagePosition);
 			mShader.drawIndexed(GL_TRIANGLES, 0, 2);
diff --git a/applications/gui/src/src_window.cpp b/applications/gui/src/src_window.cpp
index bf37129951b689ff82b6bbe8316906161c650795..0cc4a7830bade6fc5e9c6b670abc22abd4f16a62 100644
--- a/applications/gui/src/src_window.cpp
+++ b/applications/gui/src/src_window.cpp
@@ -227,7 +227,7 @@ bool SourceWindow::_processFrameset(ftl::rgbd::FrameSet &fs, bool fromstream) {
 void SourceWindow::_checkFrameSets(int id) {
 	while (framesets_.size() <= id) {
 		auto *p = ftl::config::create<ftl::operators::Graph>(screen_->root(), "pre_filters");
-		p->append<ftl::operators::DepthChannel>("depth");
+		p->append<ftl::operators::DepthChannel>("depth")->value("enabled", false);
 		//p->append<ftl::operators::ColourChannels>("colour");  // Convert BGR to BGRA
 		p->append<ftl::operators::DetectAndTrack>("facedetection")->value("enabled", false);
 		p->append<ftl::operators::ArUco>("aruco")->value("enabled", false);
diff --git a/components/codecs/include/ftl/codecs/channels.hpp b/components/codecs/include/ftl/codecs/channels.hpp
index 5af559d560a1af4c6b996d3435b3dd2c0ba4e2bf..9b0aaa1f5374130f61fbe68a6f91622c66463455 100644
--- a/components/codecs/include/ftl/codecs/channels.hpp
+++ b/components/codecs/include/ftl/codecs/channels.hpp
@@ -17,7 +17,7 @@ enum struct Channel : int {
 	Depth2			= 3,
 	Deviation		= 4,
 	Screen			= 4,
-	Normals			= 5,	// 32FC4
+	Normals			= 5,	// 16FC4
 	Weights			= 6,	// short
 	Confidence		= 7,	// 32F
 	Contribution	= 7,	// 32F
@@ -29,12 +29,13 @@ enum struct Channel : int {
 	Support1		= 13,	// 8UC4 (currently)
 	Support2		= 14,	// 8UC4 (currently)
 	Segmentation	= 15,	// 32S?
-	ColourNormals	= 16,	// 8UC4
+	Normals2		= 16,	// 16FC4
 	ColourHighRes	= 17,	// 8UC3 or 8UC4
 	LeftHighRes		= 17,	// 8UC3 or 8UC4
 	Disparity		= 18,
 	Smoothing		= 19,	// 32F
 	RightHighRes	= 20,	// 8UC3 or 8UC4
+	Colour2HighRes	= 20,
 
 	Audio			= 32,
 	AudioMono		= 32,
diff --git a/components/common/cpp/include/ftl/cuda_texture.hpp b/components/common/cpp/include/ftl/cuda_texture.hpp
index c795cd4f7a84eb97746041750b28a709524b4ea0..8edf9c3fee32ad58659b93690caf492c64a100b7 100644
--- a/components/common/cpp/include/ftl/cuda_texture.hpp
+++ b/components/common/cpp/include/ftl/cuda_texture.hpp
@@ -57,6 +57,8 @@ class TextureObjectBase {
 	__host__ __device__ inline int height() const { return height_; }
 	__host__ __device__ inline cudaTextureObject_t cudaTexture() const { return texobj_; }
 
+	cv::cuda::GpuMat to_gpumat() const;
+
 	void upload(const cv::Mat &, cudaStream_t stream=0);
 	void download(cv::Mat &, cudaStream_t stream=0) const;
 	
@@ -94,7 +96,7 @@ class TextureObject : public TextureObjectBase {
 	explicit TextureObject(const cv::cuda::GpuMat &d, bool interpolated=false);
 	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(size_t width, size_t height, bool interpolated=false);
 	TextureObject(const TextureObject<T> &t);
 	__host__ __device__ TextureObject(TextureObject<T> &&);
 	~TextureObject();
@@ -249,7 +251,7 @@ TextureObject<T>::TextureObject(T *ptr, int pitch, int width, int height) {
 }
 
 template <typename T>
-TextureObject<T>::TextureObject(size_t width, size_t height) {
+TextureObject<T>::TextureObject(size_t width, size_t height, bool interpolated) {
 	cudaMallocPitch((void**)&ptr_,&pitch_,width*sizeof(T),height);
 	cudaTextureObject_t tex = 0;
 
@@ -267,8 +269,10 @@ TextureObject<T>::TextureObject(size_t width, size_t height) {
 		cudaTextureDesc texDesc;
 		// cppcheck-suppress memsetClassFloat
 		memset(&texDesc, 0, sizeof(texDesc));
-		texDesc.readMode = cudaReadModeElementType;
-		//if (std::is_same<T,uchar4>::value) texDesc.filterMode = cudaFilterModeLinear;
+		//texDesc.readMode = cudaReadModeElementType;
+		texDesc.readMode = (interpolated) ? cudaReadModeNormalizedFloat : cudaReadModeElementType;
+		if (interpolated) texDesc.filterMode = cudaFilterModeLinear;
+
 		cudaSafeCall(cudaCreateTextureObject(&tex, &resDesc, &texDesc, NULL));
 	//}
 
diff --git a/components/common/cpp/src/cuda_common.cpp b/components/common/cpp/src/cuda_common.cpp
index 3431b6d9902ade670413f4a74178e0796994867a..2eb5d19f829c999c04cf4ec1e5c28bbd699f0521 100644
--- a/components/common/cpp/src/cuda_common.cpp
+++ b/components/common/cpp/src/cuda_common.cpp
@@ -117,6 +117,10 @@ void TextureObjectBase::download(cv::Mat &m, cudaStream_t stream) const {
 	cudaSafeCall(cudaMemcpy2DAsync(m.data, m.step, devicePtr(), pitch(), m.cols * m.elemSize(), m.rows, cudaMemcpyDeviceToHost, stream));
 }
 
+cv::cuda::GpuMat TextureObjectBase::to_gpumat() const {
+	return cv::cuda::GpuMat(height_, width_, cvType_, ptr_, pitch_);
+}
+
 
 
 BufferBase::~BufferBase() {
diff --git a/components/renderers/cpp/CMakeLists.txt b/components/renderers/cpp/CMakeLists.txt
index 71d9ad3d5df8065d11c372e19bda462cb4036f1f..1541460635fab69c057b305a6df10eea9ae29114 100644
--- a/components/renderers/cpp/CMakeLists.txt
+++ b/components/renderers/cpp/CMakeLists.txt
@@ -7,6 +7,8 @@ add_library(ftlrender
 	src/triangle_render.cu
 	src/reprojection.cu
 	src/CUDARender.cpp
+	src/colouriser.cpp
+	src/colour_util.cu
 )
 
 target_include_directories(ftlrender PUBLIC
diff --git a/components/renderers/cpp/include/ftl/render/CUDARender.hpp b/components/renderers/cpp/include/ftl/render/CUDARender.hpp
index 3d911b6accdb53001f9889a66478face2d65af77..4b74bcc490b9367eed7568a9a7d2de6b37db8e62 100644
--- a/components/renderers/cpp/include/ftl/render/CUDARender.hpp
+++ b/components/renderers/cpp/include/ftl/render/CUDARender.hpp
@@ -11,6 +11,8 @@
 namespace ftl {
 namespace render {
 
+class Colouriser;
+
 /**
  * Generate triangles between connected points and render those. Colour is done
  * by weighted reprojection to the original source images.
@@ -20,27 +22,37 @@ class CUDARender : public ftl::render::Renderer {
 	explicit CUDARender(nlohmann::json &config);
 	~CUDARender();
 
-	void begin(ftl::rgbd::Frame &) override;
+	void begin(ftl::rgbd::Frame &, ftl::codecs::Channel) override;
 	void end() override;
 
 	bool submit(ftl::rgbd::FrameSet *in, ftl::codecs::Channels<0>, const Eigen::Matrix4d &t) override;
 	//void setOutputDevice(int);
 
+	void blend(float alpha, ftl::codecs::Channel) override;
+
 	void setViewPort(ftl::render::ViewPortMode mode, const ftl::render::ViewPort &vp) {
 		params_.viewport = vp;
 		params_.viewPortMode = mode;
 	}
 
 	protected:
-	void _renderChannel(ftl::rgbd::Frame &out, ftl::codecs::Channel channel_in, ftl::codecs::Channel channel_out, const Eigen::Matrix4d &t, cudaStream_t stream);
+	void _renderChannel(ftl::rgbd::Frame &out, ftl::codecs::Channel channel_in, const Eigen::Matrix4d &t, cudaStream_t stream);
 
 	private:
 	int device_;
 	ftl::rgbd::Frame temp_;
-	ftl::rgbd::Frame accum_;
+	//ftl::rgbd::Frame accum_;
+	ftl::cuda::TextureObject<float4> accum_;		// 2 is number of channels can render together
+	ftl::cuda::TextureObject<int> contrib_;
+	//ftl::cuda::TextureObject<half4> normals_;
+
+	std::list<ftl::cuda::TextureObject<short2>*> screen_buffers_;
+	std::list<ftl::cuda::TextureObject<float>*> depth_buffers_;
+
 	ftl::rgbd::Frame *out_;
 	ftl::rgbd::FrameSet *scene_;
 	ftl::cuda::ClipSpace clip_;
+	ftl::render::Colouriser *colouriser_;
 	bool clipping_;
 	float norm_filter_;
 	bool backcull_;
@@ -57,6 +69,7 @@ class CUDARender : public ftl::render::Renderer {
 	float4x4 poseInverse_;
 	float scale_;
 	int64_t last_frame_;
+	ftl::codecs::Channel out_chan_;
 
 	cv::cuda::GpuMat env_image_;
 	ftl::cuda::TextureObject<uchar4> env_tex_;
@@ -71,25 +84,26 @@ class CUDARender : public ftl::render::Renderer {
 
 	std::vector<SubmitState> sets_;
 
-	template <typename T>
-	void __reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, const Eigen::Matrix4d &t, cudaStream_t);
-	void _reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, const Eigen::Matrix4d &t, cudaStream_t);
 	void _dibr(ftl::rgbd::Frame &, const Eigen::Matrix4d &t, cudaStream_t);
 	void _mesh(ftl::rgbd::Frame &, const Eigen::Matrix4d &t, cudaStream_t);
-	void _preprocessColours();
-	void _updateParameters(ftl::rgbd::Frame &out);
-	void _allocateChannels(ftl::rgbd::Frame &out);
+	void _updateParameters(ftl::rgbd::Frame &out, ftl::codecs::Channel);
+	void _allocateChannels(ftl::rgbd::Frame &out, ftl::codecs::Channel);
 	void _postprocessColours(ftl::rgbd::Frame &out);
 
-	void _renderNormals(ftl::rgbd::Frame &out);
-	void _renderDensity(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t);
-	void _renderRight(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t);
-	void _renderSecond(ftl::rgbd::Frame &out, ftl::codecs::Channel chan, const Eigen::Matrix4d &t);
 	void _renderPass1(const Eigen::Matrix4d &t);
 	void _renderPass2(ftl::codecs::Channels<0>, const Eigen::Matrix4d &t);
 
+	void _end();
+	void _endSubmit();
+
 	bool _alreadySeen() const { return last_frame_ == scene_->timestamp; }
 	void _adjustDepthThresholds(const ftl::rgbd::Camera &fcam);
+
+	ftl::cuda::TextureObject<float> &_getDepthBuffer(const cv::Size &);
+	ftl::cuda::TextureObject<short2> &_getScreenBuffer(const cv::Size &);
+
+	inline ftl::codecs::Channel _getDepthChannel() const { return (out_chan_ == ftl::codecs::Channel::Colour) ? ftl::codecs::Channel::Depth : ftl::codecs::Channel::Depth2; }
+	inline ftl::codecs::Channel _getNormalsChannel() const { return (out_chan_ == ftl::codecs::Channel::Colour) ? ftl::codecs::Channel::Normals : ftl::codecs::Channel::Normals2; }
 };
 
 }
diff --git a/components/renderers/cpp/include/ftl/render/colouriser.hpp b/components/renderers/cpp/include/ftl/render/colouriser.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..0df2f81d6a55e6ab44049049489ce0faab64124c
--- /dev/null
+++ b/components/renderers/cpp/include/ftl/render/colouriser.hpp
@@ -0,0 +1,44 @@
+#ifndef _FTL_RENDER_COLOURISER_HPP_
+#define _FTL_RENDER_COLOURISER_HPP_
+
+#include <ftl/configurable.hpp>
+#include <ftl/cuda_common.hpp>
+#include <ftl/rgbd/frame.hpp>
+#include <ftl/codecs/channels.hpp>
+
+namespace ftl {
+namespace render {
+
+uchar4 parseCUDAColour(const std::string &colour);
+cv::Scalar parseCVColour(const std::string &colour);
+
+/**
+ * Generate a colour texture for any frame channel. It also can modify the
+ * existing colour channels. All settings come from the json config.
+ */
+class Colouriser : public ftl::Configurable {
+	public:
+	explicit Colouriser(nlohmann::json &config);
+	~Colouriser();
+
+	ftl::cuda::TextureObject<uchar4> &colourise(ftl::rgbd::Frame &f, ftl::codecs::Channel, cudaStream_t stream);
+
+	private:
+	std::list<ftl::cuda::TextureObject<uchar4>*> textures_;
+	cv::cuda::GpuMat depth_gray_;
+	cv::cuda::GpuMat depth_bgr_;
+
+	ftl::cuda::TextureObject<uchar4> &_getBuffer(size_t width, size_t height);
+
+	template <typename T>
+	ftl::cuda::TextureObject<uchar4> &_processSingle(ftl::rgbd::Frame &f, ftl::codecs::Channel c, cudaStream_t stream);
+
+	ftl::cuda::TextureObject<uchar4> &_processColour(ftl::rgbd::Frame &f, ftl::codecs::Channel c, cudaStream_t stream);
+	ftl::cuda::TextureObject<uchar4> &_processNormals(ftl::rgbd::Frame &f, ftl::codecs::Channel c, cudaStream_t stream);
+	ftl::cuda::TextureObject<uchar4> &_processFloat(ftl::rgbd::Frame &f, ftl::codecs::Channel c, float minval, float maxval, cudaStream_t stream);
+};
+
+}
+}
+
+#endif
\ No newline at end of file
diff --git a/components/renderers/cpp/include/ftl/render/renderer.hpp b/components/renderers/cpp/include/ftl/render/renderer.hpp
index ec479ce51e3b494b4df6818303c1aeb5db480bad..5d9d55f13fc3447e2ec6112694056474bc837a8b 100644
--- a/components/renderers/cpp/include/ftl/render/renderer.hpp
+++ b/components/renderers/cpp/include/ftl/render/renderer.hpp
@@ -8,6 +8,12 @@
 namespace ftl {
 namespace render {
 
+enum class Stage {
+	Finished,
+	ReadySubmit,
+	Blending
+};
+
 /**
  * Abstract class for all renderers. A renderer takes some 3D scene and
  * generates a virtual camera perspective of that scene. The scene might be
@@ -18,14 +24,17 @@ namespace render {
  */
 class Renderer : public ftl::Configurable {
     public:
-    explicit Renderer(nlohmann::json &config) : Configurable(config) {};
+    explicit Renderer(nlohmann::json &config) : Configurable(config), stage_(Stage::Finished) {};
     virtual ~Renderer() {};
 
 	/**
 	 * Begin a new render. This clears memory, allocates buffers etc. The RGBD
 	 * frame given as parameter is where the output channels are rendered to.
+	 * The channel parameter is the render output channel which can either be
+	 * Left (Colour) or Right (Colour 2). Using "Right" will also adjust the
+	 * pose to the right eye position and use the right camera intrinsics. 
 	 */
-	virtual void begin(ftl::rgbd::Frame &)=0;
+	virtual void begin(ftl::rgbd::Frame &, ftl::codecs::Channel)=0;
 
 	/**
 	 * Finish a render. Post process the output as required, or finish
@@ -38,9 +47,19 @@ class Renderer : public ftl::Configurable {
      * Render all frames of a frameset into the output frame. This can be called
 	 * multiple times between `begin` and `end` to combine multiple framesets.
 	 * Note that the frameset pointer must remain valid until `end` is called,
-	 * and ideally should not be swapped between
+	 * and ideally should not be swapped between.
+	 * 
+	 * The channels parameter gives all of the source channels that will be
+	 * rendered into the single colour output. These will be blended
+	 * together by some undefined method. Non colour channels will be converted
+	 * to RGB colour appropriately.
      */
     virtual bool submit(ftl::rgbd::FrameSet *, ftl::codecs::Channels<0>, const Eigen::Matrix4d &)=0;
+
+	virtual void blend(float, ftl::codecs::Channel)=0;
+
+	protected:
+	Stage stage_;
 };
 
 }
diff --git a/components/renderers/cpp/src/CUDARender.cpp b/components/renderers/cpp/src/CUDARender.cpp
index 799b990f26d28acc533f38b0739b30b2260deaca..9dec33bcbf46369f18ce5989f02bd5bd4bcc7ee5 100644
--- a/components/renderers/cpp/src/CUDARender.cpp
+++ b/components/renderers/cpp/src/CUDARender.cpp
@@ -4,6 +4,9 @@
 #include <ftl/cuda/points.hpp>
 #include <ftl/cuda/normals.hpp>
 #include <ftl/operators/mask_cuda.hpp>
+#include <ftl/render/colouriser.hpp>
+
+#include "colour_cuda.hpp"
 
 #define LOGURU_REPLACE_GLOG 1
 #include <loguru.hpp>
@@ -11,6 +14,7 @@
 #include <opencv2/imgcodecs.hpp>
 #include <opencv2/imgproc.hpp>
 #include <opencv2/core/cuda_stream_accessor.hpp>
+#include <opencv2/cudaarithm.hpp>
 
 //#include <ftl/filters/smoothing.hpp>
 
@@ -23,6 +27,8 @@ using ftl::rgbd::Format;
 using cv::cuda::GpuMat;
 using std::stoul;
 using ftl::cuda::Mask;
+using ftl::render::parseCUDAColour;
+using ftl::render::parseCVColour;
 
 static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) {
   Eigen::Affine3d rx =
@@ -34,44 +40,6 @@ static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) {
   return rz * rx * ry;
 }
 
-/*
- * Parse a CSS style colour string into a scalar.
- */
-static cv::Scalar parseCVColour(const std::string &colour) {
-	std::string c = colour;
-	if (c[0] == '#') {
-		c.erase(0, 1);
-		unsigned long value = stoul(c.c_str(), nullptr, 16);
-		return cv::Scalar(
-			(value >> 0) & 0xff,
-			(value >> 8) & 0xff,
-			(value >> 16) & 0xff,
-			(value >> 24) & 0xff
-		);
-	}
-
-	return cv::Scalar(0,0,0,0);
-}
-
-/*
- * Parse a CSS style colour string into a scalar.
- */
-static uchar4 parseCUDAColour(const std::string &colour) {
-	std::string c = colour;
-	if (c[0] == '#') {
-		c.erase(0, 1);
-		unsigned long value = stoul(c.c_str(), nullptr, 16);
-		return make_uchar4(
-			(value >> 0) & 0xff,
-			(value >> 8) & 0xff,
-			(value >> 16) & 0xff,
-			(value >> 24) & 0xff
-		);
-	}
-
-	return make_uchar4(0,0,0,0);
-}
-
 CUDARender::CUDARender(nlohmann::json &config) : ftl::render::Renderer(config), scene_(nullptr) {
 	/*if (config["clipping"].is_object()) {
 		auto &c = config["clipping"];
@@ -98,6 +66,8 @@ CUDARender::CUDARender(nlohmann::json &config) : ftl::render::Renderer(config),
 
 	params_.viewPortMode = ftl::render::ViewPortMode::Disabled;
 
+	colouriser_ = ftl::create<ftl::render::Colouriser>(this, "colouriser");
+
 	on("clipping_enabled", [this](const ftl::config::Event &e) {
 		clipping_ = value("clipping_enabled", true);
 	});
@@ -122,21 +92,6 @@ CUDARender::CUDARender(nlohmann::json &config) : ftl::render::Renderer(config),
 		background_ = parseCVColour(value("background", std::string("#4c4c4c")));
 	});
 
-	light_diffuse_ = parseCUDAColour(value("diffuse", std::string("#e0e0e0")));
-	on("diffuse", [this](const ftl::config::Event &e) {
-		light_diffuse_ = parseCUDAColour(value("diffuse", std::string("#e0e0e0")));
-	});
-
-	light_ambient_ = parseCUDAColour(value("ambient", std::string("#0e0e0e")));
-	on("ambient", [this](const ftl::config::Event &e) {
-		light_ambient_ = parseCUDAColour(value("ambient", std::string("#0e0e0e")));
-	});
-
-	light_pos_ = make_float3(value("light_x", 0.3f), value("light_y", 0.2f), value("light_z", 1.0f));
-	on("light_x", [this](const ftl::config::Event &e) { light_pos_.x = value("light_x", 0.3f); });
-	on("light_y", [this](const ftl::config::Event &e) { light_pos_.y = value("light_y", 0.3f); });
-	on("light_z", [this](const ftl::config::Event &e) { light_pos_.z = value("light_z", 0.3f); });
-
 	// Load any environment texture
 	std::string envimage = value("environment", std::string(""));
 	if (envimage.size() > 0) {
@@ -151,9 +106,6 @@ CUDARender::CUDARender(nlohmann::json &config) : ftl::render::Renderer(config),
 	}
 
 	cudaSafeCall(cudaStreamCreate(&stream_));
-
-	//filters_ = ftl::create<ftl::Filters>(this, "filters");
-	//filters_->create<ftl::filters::DepthSmoother>("hfnoise");
 	last_frame_ = -1;
 }
 
@@ -161,24 +113,11 @@ CUDARender::~CUDARender() {
 
 }
 
-template <typename T>
-struct AccumSelector {
-	typedef float4 type;
-	static constexpr Channel channel = Channel::Colour;
-	//static constexpr cv::Scalar value = cv::Scalar(0.0f,0.0f,0.0f,0.0f);
-};
-
-template <>
-struct AccumSelector<float> {
-	typedef float type;
-	static constexpr Channel channel = Channel::Colour2;
-	//static constexpr cv::Scalar value = cv::Scalar(0.0f);
-};
-
-template <typename T>
-void CUDARender::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, const Eigen::Matrix4d &t, cudaStream_t stream) {
+void CUDARender::_renderChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, const Eigen::Matrix4d &t, cudaStream_t stream) {
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 
+	if (in == Channel::None) return;
+
 	for (size_t i=0; i < scene_->frames.size(); ++i) {
 		auto &f = scene_->frames[i];
 
@@ -189,71 +128,37 @@ void CUDARender::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann
 
 		_adjustDepthThresholds(f.getLeftCamera());
 
+		// Generate a colour texture from any channel
+		auto &texture = colouriser_->colourise(f, in, stream);
+
 		auto transform = MatrixConversion::toCUDA(f.getPose().cast<float>().inverse() * t.cast<float>().inverse()) * poseInverse_;
 		auto transformR = MatrixConversion::toCUDA(f.getPose().cast<float>().inverse()).getFloat3x3();
 
-		//if (mesh_) {
-			if (f.hasChannel(Channel::Depth)) {
-				ftl::cuda::reproject(
-					f.createTexture<T>(in),
-					f.createTexture<float>(Channel::Depth),
-					output.getTexture<float>(Channel::Depth),
-					f.createTexture<short>(Channel::Weights),
-					(output.hasChannel(Channel::Normals)) ? &output.createTexture<half4>(Channel::Normals) : nullptr,
-					temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
-					temp_.getTexture<int>(Channel::Contribution),
-					params_,
-					f.getLeftCamera(),
-					transform, transformR, stream
-				);
-			} else {
-				// Reproject without depth channel or normals
-				ftl::cuda::reproject(
-					f.createTexture<T>(in),
-					output.getTexture<float>(Channel::Depth),
-					temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
-					temp_.getTexture<int>(Channel::Contribution),
-					params_,
-					f.getLeftCamera(),
-					transform, stream
-				);
-			}
-		/*} else {
-			// Can't use normals with point cloud version
-			if (f.hasChannel(Channel::Depth)) {
-				ftl::cuda::reproject(
-					f.createTexture<T>(in),
-					f.createTexture<float>(Channel::Depth),
-					output.getTexture<float>(Channel::Depth),
-					temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
-					temp_.getTexture<int>(Channel::Contribution),
-					params_,
-					f.getLeftCamera(),
-					transform, stream
-				);
-			} else {
-				ftl::cuda::reproject(
-					f.createTexture<T>(in),
-					output.getTexture<float>(Channel::Depth),
-					temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
-					temp_.getTexture<int>(Channel::Contribution),
-					params_,
-					f.getLeftCamera(),
-					transform, stream
-				);
-			}
-		}*/
-	}
-}
-
-void CUDARender::_reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, const Eigen::Matrix4d &t, cudaStream_t stream) {
-	int type = output.get<GpuMat>(out).type(); // == CV_32F; //ftl::rgbd::isFloatChannel(channel);
-	
-	switch (type) {
-	case CV_32F		: __reprojectChannel<float>(output, in, out, t, stream); break;
-	case CV_32FC4	: __reprojectChannel<float4>(output, in, out, t, stream); break;
-	case CV_8UC4	: __reprojectChannel<uchar4>(output, in, out, t, stream); break;
-	default			: LOG(ERROR) << "Invalid output channel format";
+		if (f.hasChannel(Channel::Depth)) {
+			ftl::cuda::reproject(
+				texture,
+				f.createTexture<float>(Channel::Depth),
+				output.getTexture<float>(_getDepthChannel()),
+				f.createTexture<short>(Channel::Weights),
+				(mesh_) ? &output.getTexture<half4>(_getNormalsChannel()) : nullptr,
+				accum_,
+				contrib_,
+				params_,
+				f.getLeftCamera(),
+				transform, transformR, stream
+			);
+		} else {
+			// Reproject without depth channel or normals
+			ftl::cuda::reproject(
+				texture,
+				output.getTexture<float>(_getDepthChannel()),
+				accum_,
+				contrib_,
+				params_,
+				f.getLeftCamera(),
+				transform, stream
+			);
+		}
 	}
 }
 
@@ -291,13 +196,31 @@ void CUDARender::_dibr(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 	}
 
 	// Convert from int depth to float depth
-	temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(Channel::Depth), CV_32F, 1.0f / 100000.0f, cvstream);
+	temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(_getDepthChannel()), CV_32F, 1.0f / 100000.0f, cvstream);
 }
 
 void CUDARender::_adjustDepthThresholds(const ftl::rgbd::Camera &fcam) {
 	params_.depthCoef = fcam.baseline*fcam.fx;
 }
 
+ftl::cuda::TextureObject<float> &CUDARender::_getDepthBuffer(const cv::Size &size) {
+	for (auto *b : depth_buffers_) {
+		if (b->width() == size.width && b->height() == size.height) return *b;
+	}
+	auto *nb = new ftl::cuda::TextureObject<float>(size.width, size.height);
+	depth_buffers_.push_back(nb);
+	return *nb;
+}
+
+ftl::cuda::TextureObject<short2> &CUDARender::_getScreenBuffer(const cv::Size &size) {
+	for (auto *b : screen_buffers_) {
+		if (b->width() == size.width && b->height() == size.height) return *b;
+	}
+	auto *nb = new ftl::cuda::TextureObject<short2>(size.width, size.height);
+	screen_buffers_.push_back(nb);
+	return *nb;
+}
+
 void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStream_t stream) {
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 
@@ -306,8 +229,6 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 	if (do_blend) {
 		temp_.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(0x7FFFFFFF), cvstream);
 		temp_.get<GpuMat>(Channel::Weights).setTo(cv::Scalar(0.0f), cvstream);
-		// FIXME: Doesnt work with multiple compositing
-		out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
 	} else {
 		temp_.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0x7FFFFFFF), cvstream);
 	}
@@ -327,19 +248,23 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 
 		_adjustDepthThresholds(f.getLeftCamera());
 
+		auto bufsize = f.get<GpuMat>((f.hasChannel(Channel::Depth)) ? Channel::Depth : Channel::Colour).size();
+		auto &depthbuffer = _getDepthBuffer(bufsize);
+		auto &screenbuffer = _getScreenBuffer(bufsize);
+
 		// Calculate and save virtual view screen position of each source pixel
 		if (f.hasChannel(Channel::Depth)) {
 			ftl::cuda::screen_coord(
 				f.createTexture<float>(Channel::Depth),
-				f.createTexture<float>(Channel::Depth2, Format<float>(f.get<GpuMat>(Channel::Depth).size())),
-				f.createTexture<short2>(Channel::Screen, Format<short2>(f.get<GpuMat>(Channel::Depth).size())),
+				depthbuffer,
+				screenbuffer,
 				params_, transform, f.getLeftCamera(), stream
 			);
 		} else {
 			// Constant depth version
 			ftl::cuda::screen_coord(
-				f.createTexture<float>(Channel::Depth2, Format<float>(f.get<GpuMat>(Channel::Colour).size())),
-				f.createTexture<short2>(Channel::Screen, Format<short2>(f.get<GpuMat>(Channel::Colour).size())),
+				depthbuffer,
+				screenbuffer,
 				params_, transform, f.getLeftCamera(), stream
 			);
 		}
@@ -351,9 +276,9 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 
 		// Decide on and render triangles around each point
 		ftl::cuda::triangle_render1(
-			f.getTexture<float>(Channel::Depth2),
+			depthbuffer,
 			temp_.createTexture<int>((do_blend) ? Channel::Depth : Channel::Depth2),
-			f.getTexture<short2>(Channel::Screen),
+			screenbuffer,
 			params_, stream
 		);
 
@@ -364,8 +289,7 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 			// Blend this sources mesh with previous meshes
 			ftl::cuda::mesh_blender(
 				temp_.getTexture<int>(Channel::Depth),
-				//temp_.createTexture<int>(Channel::Depth2),
-				out.createTexture<float>(Channel::Depth),
+				out.createTexture<float>(_getDepthChannel()),
 				f.createTexture<short>(Channel::Weights),
 				temp_.createTexture<float>(Channel::Weights),
 				params_,
@@ -382,166 +306,92 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 
 	if (do_blend) {
 		ftl::cuda::dibr_normalise(
-			out.getTexture<float>(Channel::Depth),
-			out.getTexture<float>(Channel::Depth),
+			out.getTexture<float>(_getDepthChannel()),
+			out.getTexture<float>(_getDepthChannel()),
 			temp_.getTexture<float>(Channel::Weights),
 			stream_
 		);
 	} else {
-		ftl::cuda::merge_convert_depth(temp_.getTexture<int>(Channel::Depth2), out.createTexture<float>(Channel::Depth), 1.0f / 100000.0f, stream_);
+		ftl::cuda::merge_convert_depth(temp_.getTexture<int>(Channel::Depth2), out.createTexture<float>(_getDepthChannel()), 1.0f / 100000.0f, stream_);
 	}
 
 	//filters_->filter(out, src, stream);
 
 	// Generate normals for final virtual image
-	ftl::cuda::normals(out.createTexture<half4>(Channel::Normals, Format<half4>(params_.camera.width, params_.camera.height)),
-				temp_.createTexture<half4>(Channel::Normals),
-				out.createTexture<float>(Channel::Depth),
-				value("normal_radius", 1), value("normal_smoothing", 0.02f),
-				params_.camera, pose_.getFloat3x3(), poseInverse_.getFloat3x3(), stream_);
-}
-
-void CUDARender::_renderChannel(
-		ftl::rgbd::Frame &out,
-		Channel channel_in, Channel channel_out, const Eigen::Matrix4d &t, cudaStream_t stream)
-{
-	if (channel_out == Channel::None || channel_in == Channel::None) return;
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
-
-	if (scene_->frames.size() < 1) return;
-	bool is_float = out.get<GpuMat>(channel_out).type() == CV_32F; //ftl::rgbd::isFloatChannel(channel);
-	bool is_4chan = out.get<GpuMat>(channel_out).type() == CV_32FC4;
-
-
-	temp_.createTexture<float4>(Channel::Colour);
-	temp_.createTexture<int>(Channel::Contribution);
-
-	// FIXME: Using colour 2 in this way seems broken since it is already used
-	if (is_4chan) {
-		accum_.create<GpuMat>(channel_out, Format<float4>(params_.camera.width, params_.camera.height));
-		accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0.0f,0.0f,0.0f,0.0f), cvstream);
-	} else if (is_float) {
-		accum_.create<GpuMat>(channel_out, Format<float>(params_.camera.width, params_.camera.height));
-		accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0.0f), cvstream);
-	} else {
-		accum_.create<GpuMat>(channel_out, Format<uchar4>(params_.camera.width, params_.camera.height));
-		accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0,0,0,0), cvstream);
-	}
-
-	_reprojectChannel(out, channel_in, channel_out, t, stream);
+	ftl::cuda::normals(
+		out.createTexture<half4>(_getNormalsChannel()),
+		temp_.createTexture<half4>(Channel::Normals),
+		out.getTexture<float>(_getDepthChannel()),
+		value("normal_radius", 1), value("normal_smoothing", 0.02f),
+		params_.camera, pose_.getFloat3x3(), poseInverse_.getFloat3x3(), stream_);
 }
 
-/*
- * H(Hue): 0 - 360 degree (integer)
- * S(Saturation): 0 - 1.00 (double)
- * V(Value): 0 - 1.00 (double)
- * 
- * output[3]: Output, array size 3, int
- */
-static cv::Scalar HSVtoRGB(int H, double S, double V) {
-	double C = S * V;
-	double X = C * (1 - abs(fmod(H / 60.0, 2) - 1));
-	double m = V - C;
-	double Rs, Gs, Bs;
-
-	if(H >= 0 && H < 60) {
-		Rs = C;
-		Gs = X;
-		Bs = 0;	
-	}
-	else if(H >= 60 && H < 120) {	
-		Rs = X;
-		Gs = C;
-		Bs = 0;	
-	}
-	else if(H >= 120 && H < 180) {
-		Rs = 0;
-		Gs = C;
-		Bs = X;	
-	}
-	else if(H >= 180 && H < 240) {
-		Rs = 0;
-		Gs = X;
-		Bs = C;	
-	}
-	else if(H >= 240 && H < 300) {
-		Rs = X;
-		Gs = 0;
-		Bs = C;	
-	}
-	else {
-		Rs = C;
-		Gs = 0;
-		Bs = X;	
-	}
-
-	return cv::Scalar((Bs + m) * 255, (Gs + m) * 255, (Rs + m) * 255, 0);
-}
-
-void CUDARender::_allocateChannels(ftl::rgbd::Frame &out) {
-	const auto &camera = out.getLeftCamera();
+void CUDARender::_allocateChannels(ftl::rgbd::Frame &out, ftl::codecs::Channel chan) {
+	const auto &camera = params_.camera;
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
 
-	// Only do this if not already done, allows for multiple render passes with
-	// different framesets.
-	if (!out.hasChannel(Channel::Depth)) {
-		out.create<GpuMat>(Channel::Depth, Format<float>(camera.width, camera.height));
-		out.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height));
-		out.createTexture<uchar4>(Channel::Colour, true);  // Force interpolated colour
-		out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
+	// Allocate left channel buffers and clear them
+	if (chan == Channel::Colour) {
+		if (!out.hasChannel(Channel::Depth)) {
+			out.create<GpuMat>(Channel::Depth, Format<float>(camera.width, camera.height));
+			out.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height));
+			out.create<GpuMat>(Channel::Normals, Format<half4>(camera.width, camera.height));
+			out.createTexture<uchar4>(Channel::Colour, true);  // Force interpolated colour
+			out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
+		}
+	// Allocate right channel buffers and clear them
+	} else {
+		if (!out.hasChannel(Channel::Depth2)) {
+			out.create<GpuMat>(Channel::Depth2, Format<float>(camera.width, camera.height));
+			out.create<GpuMat>(Channel::Colour2, Format<uchar4>(camera.width, camera.height));
+			out.create<GpuMat>(Channel::Normals2, Format<half4>(camera.width, camera.height));
+			out.createTexture<uchar4>(Channel::Colour2, true);  // Force interpolated colour
+			out.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(1000.0f), cvstream);
+		}
 	}
 
-	temp_.create<GpuMat>(Channel::Colour, Format<float4>(camera.width, camera.height));
-	temp_.create<GpuMat>(Channel::Contribution, Format<int>(camera.width, camera.height));
 	temp_.create<GpuMat>(Channel::Depth, Format<int>(camera.width, camera.height));
 	temp_.create<GpuMat>(Channel::Depth2, Format<int>(camera.width, camera.height));
 	temp_.create<GpuMat>(Channel::Normals, Format<half4>(camera.width, camera.height));
 	temp_.create<GpuMat>(Channel::Weights, Format<float>(camera.width, camera.height));
 	temp_.createTexture<int>(Channel::Depth);
+
+	accum_.create(camera.width, camera.height);
+	contrib_.create(camera.width, camera.height);
+
+	// Must clear the colour accumulation buffers each frame
+	cv::cuda::GpuMat accum(accum_.height(), accum_.width(), CV_32FC4, accum_.devicePtr(), accum_.pitch());
+	accum.setTo(cv::Scalar(0.0f,0.0f,0.0f,0.0f), cvstream);
+	cv::cuda::GpuMat contrib(contrib_.height(), contrib_.width(), CV_32S, contrib_.devicePtr(), contrib_.pitch());
+	contrib.setTo(cv::Scalar(0), cvstream);
+
+	//normals_.create(camera.width, camera.height);
 }
 
-void CUDARender::_updateParameters(ftl::rgbd::Frame &out) {
-	const auto &camera = out.getLeftCamera();
+void CUDARender::_updateParameters(ftl::rgbd::Frame &out, ftl::codecs::Channel chan) {
+	const auto &camera = (chan == Channel::Right) ? out.getRightCamera() : out.getLeftCamera();
+	params_.camera = camera;
+
+	if (chan == Channel::Right) {
+		// Right channel needs to adjust pose by a baseline translation
+		float baseline = params_.camera.baseline;
+		Eigen::Matrix4f transform = Eigen::Matrix4f::Identity();
+		transform(0, 3) = baseline;
+		Eigen::Matrix4f matrix = out.getPose().cast<float>() * transform.inverse();
+		pose_ = MatrixConversion::toCUDA(matrix.inverse());
+		poseInverse_ = MatrixConversion::toCUDA(matrix);
+	} else {
+		poseInverse_ = MatrixConversion::toCUDA(out.getPose().cast<float>());
+		pose_ = MatrixConversion::toCUDA(out.getPose().cast<float>().inverse());
+	}
 
 	// Parameters object to pass to CUDA describing the camera
 	params_.triangle_limit = value("triangle_limit", 200);
-	//params_.depthThreshold = value("depth_threshold", 0.004f);
-	//params_.depthThreshScale = value("depth_thresh_scale", 0.166f);  // baseline*focal / disp....
 	params_.disconDisparities = value("discon_disparities", 2.0f);
 	params_.accumulationMode = static_cast<ftl::render::AccumulationFunction>(value("accumulation_func", 0));
 	params_.m_flags = 0;
 	if (value("normal_weight_colours", true)) params_.m_flags |= ftl::render::kNormalWeightColours;
 	if (value("channel_weights", false)) params_.m_flags |= ftl::render::kUseWeightsChannel;
-	params_.camera = camera;
-
-	poseInverse_ = MatrixConversion::toCUDA(out.getPose().cast<float>());
-	pose_ = MatrixConversion::toCUDA(out.getPose().cast<float>().inverse());
-}
-
-void CUDARender::_preprocessColours() {
-	uint8_t show_mask = value("show_mask", 0);
-	bool colour_sources = value("colour_sources", false);
-
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-
-	// Display mask values or otherwise alter colour image
-	for (size_t i=0; i<scene_->frames.size(); ++i) {
-		auto &f = scene_->frames[i];
-
-		if (colour_sources) {
-			auto colour = HSVtoRGB(360 / scene_->frames.size() * i, 0.6, 0.85);
-			f.get<GpuMat>(Channel::Colour).setTo(colour, cvstream);
-		}
-
-		if (f.hasChannel(Channel::Mask)) {
-			if (show_mask > 0) {
-				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<uint8_t>(Channel::Mask), show_mask, make_uchar4(255,0,255,255), stream_);
-			}
-		}
-
-		// Force interpolated colour
-		f.createTexture<uchar4>(Channel::Colour, true);
-	}
 }
 
 void CUDARender::_postprocessColours(ftl::rgbd::Frame &out) {
@@ -550,8 +400,8 @@ void CUDARender::_postprocessColours(ftl::rgbd::Frame &out) {
 		auto col = parseCUDAColour(value("cool_effect_colour", std::string("#2222ff")));
 
 		ftl::cuda::cool_blue(
-			out.getTexture<half4>(Channel::Normals),
-			out.getTexture<uchar4>(Channel::Colour),
+			out.getTexture<half4>(_getNormalsChannel()),
+			out.getTexture<uchar4>(out_chan_),
 			col, pose,
 			stream_	
 		);
@@ -559,25 +409,25 @@ void CUDARender::_postprocessColours(ftl::rgbd::Frame &out) {
 
 	if (value("show_colour_weights", false)) {
 		ftl::cuda::show_colour_weights(
-			out.getTexture<uchar4>(Channel::Colour),
-			temp_.getTexture<int>(Channel::Contribution),
+			out.getTexture<uchar4>(out_chan_),
+			contrib_,
 			make_uchar4(0,0,255,0),
 			stream_
 		);
 	} else if (value("show_bad_colour", false)) {
 		ftl::cuda::show_missing_colour(
-			out.getTexture<float>(Channel::Depth),
-			out.getTexture<uchar4>(Channel::Colour),
-			temp_.getTexture<int>(Channel::Contribution),
+			out.getTexture<float>(_getDepthChannel()),
+			out.getTexture<uchar4>(out_chan_),
+			contrib_,
 			make_uchar4(255,0,0,0),
 			params_.camera,
 			stream_
 		);
-	} else if (out.hasChannel(Channel::Depth) && out.hasChannel(Channel::Colour) && temp_.hasChannel(Channel::Contribution)) {
+	} else if (out.hasChannel(_getDepthChannel()) && out.hasChannel(out_chan_)) {
 		ftl::cuda::fix_bad_colour(
-			out.getTexture<float>(Channel::Depth),
-			out.getTexture<uchar4>(Channel::Colour),
-			temp_.getTexture<int>(Channel::Contribution),
+			out.getTexture<float>(_getDepthChannel()),
+			out.getTexture<uchar4>(out_chan_),
+			contrib_,
 			make_uchar4(255,0,0,0),
 			params_.camera,
 			stream_
@@ -585,71 +435,10 @@ void CUDARender::_postprocessColours(ftl::rgbd::Frame &out) {
 	}
 }
 
-void CUDARender::_renderNormals(ftl::rgbd::Frame &out) {
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-
-	// Visualise normals to RGBA
-	out.create<GpuMat>(Channel::ColourNormals, Format<uchar4>(params_.camera.width, params_.camera.height)).setTo(cv::Scalar(0,0,0,0), cvstream);
-
-	ftl::cuda::normal_visualise(out.getTexture<half4>(Channel::Normals), out.createTexture<uchar4>(Channel::ColourNormals),
-			light_pos_,
-			light_diffuse_,
-			light_ambient_, stream_);
-}
-
-void CUDARender::_renderDensity(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t) {
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-	out.create<GpuMat>(Channel::Density, Format<float>(params_.camera.width, params_.camera.height));
-	out.get<GpuMat>(Channel::Density).setTo(cv::Scalar(0.0f), cvstream);
-	_renderChannel(out, Channel::Depth, Channel::Density, t, stream_);
-}
-
-void CUDARender::_renderRight(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t) {
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-
-	float baseline = params_.camera.baseline;
-
-	Eigen::Matrix4f transform = Eigen::Matrix4f::Identity();
-	transform(0, 3) = baseline;
-	Eigen::Matrix4f matrix = out.getPose().cast<float>() * transform.inverse();
-	
-	pose_ = MatrixConversion::toCUDA(matrix.inverse());
-	poseInverse_ = MatrixConversion::toCUDA(matrix);
-	params_.camera = out.getRightCamera();
-	
-	out.create<GpuMat>(Channel::Right, Format<uchar4>(params_.camera.width, params_.camera.height));
-	out.get<GpuMat>(Channel::Right).setTo(background_, cvstream);
-	out.createTexture<uchar4>(Channel::Right, true);
-
-	// Need to re-dibr due to pose change
-	if (mesh_) {
-		_mesh(out, t, stream_);
-	} else {
-		_dibr(out, t, stream_);
-	}
-	_renderChannel(out, Channel::Left, Channel::Right, t, stream_);
-}
-
-void CUDARender::_renderSecond(ftl::rgbd::Frame &out, ftl::codecs::Channel chan, const Eigen::Matrix4d &t) {
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-
-	if (ftl::codecs::isFloatChannel(chan)) {
-		out.create<GpuMat>(chan, Format<float>(params_.camera.width, params_.camera.height));
-		out.get<GpuMat>(chan).setTo(cv::Scalar(0.0f), cvstream);
-	} else {
-		out.create<GpuMat>(chan, Format<uchar4>(params_.camera.width, params_.camera.height));
-		out.get<GpuMat>(chan).setTo(background_, cvstream);
-	}
-	_renderChannel(out, chan, chan, t, stream_);
-}
-
 void CUDARender::_renderPass1(const Eigen::Matrix4d &t) {
-	const auto &camera = out_->getLeftCamera();
+	//const auto &camera = out_->getLeftCamera();
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
 
-	// Render source specific debug info into colour channels
-	_preprocessColours();
-
 	if (mesh_) {
 		// Render depth channel using triangles
 		_mesh(*out_, t, stream_);
@@ -660,42 +449,35 @@ void CUDARender::_renderPass1(const Eigen::Matrix4d &t) {
 }
 
 void CUDARender::_renderPass2(Channels<0> chans, const Eigen::Matrix4d &t) {
-	const auto &camera = out_->getLeftCamera();
-	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
-
-	// Reprojection of colours onto surface
-	auto main_channel = (scene_->frames[0].hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : Channel::Colour;
-	_renderChannel(*out_, main_channel, Channel::Colour, t, stream_);
+	for (auto chan : chans) {
+		ftl::codecs::Channel mapped = chan;
 
+		if (chan == Channel::Colour && scene_->frames[0].hasChannel(Channel::ColourHighRes)) mapped = Channel::ColourHighRes;
 
-	// Support rendering of a second channel without redoing all the work
-	for (auto chan : chans) {
-		switch(chan) {
-		case Channel::None			:
-		case Channel::Left			:
-		case Channel::Depth			: break;
-		case Channel::Normals		: 
-		case Channel::ColourNormals	: _renderNormals(*out_); break;
-		case Channel::Density		: _renderDensity(*out_, t); break;
-		case Channel::Right			: _renderRight(*out_, t); break;
-		default						: _renderSecond(*out_, chan, t);
-		}
+		_renderChannel(*out_, mapped, t, stream_);
 	}
 }
 
-void CUDARender::begin(ftl::rgbd::Frame &out) {
+void CUDARender::begin(ftl::rgbd::Frame &out, ftl::codecs::Channel chan) {
+	if (stage_ != Stage::Finished) {
+		throw FTL_Error("Already rendering");
+	}
+
 	out_ = &out;
 	const auto &camera = out.getLeftCamera();
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
 
-	_updateParameters(out);
+	if (chan != Channel::Colour && chan != Channel::Colour2) {
+		throw FTL_Error("Can only render to Left or Right channels");
+	}
 
-	// Create all the required channels
-	_allocateChannels(out);
+	out_chan_ = chan;
+	_updateParameters(out, chan);
+	_allocateChannels(out, chan);
 
 	// Apply a colour background
 	if (env_image_.empty() || !value("environment_enabled", false)) {
-		out.get<GpuMat>(Channel::Colour).setTo(background_, cvstream);
+		out.get<GpuMat>(chan).setTo(background_, cvstream);
 	} else {
 		auto pose = poseInverse_.getFloat3x3();
 		ftl::cuda::equirectangular_reproject(
@@ -704,25 +486,38 @@ void CUDARender::begin(ftl::rgbd::Frame &out) {
 			camera, pose, stream_);
 	}
 
-	temp_.create<GpuMat>(
-		AccumSelector<uchar4>::channel,
-		Format<typename AccumSelector<uchar4>::type>(params_.camera.width, params_.camera.height)
-	).setTo(cv::Scalar(0.0f), cvstream);
-	temp_.get<GpuMat>(Channel::Contribution).setTo(cv::Scalar(0), cvstream);
+	sets_.clear();
+	stage_ = Stage::ReadySubmit;
+}
+
+void CUDARender::blend(float alpha, Channel c) {
+	if (stage_ == Stage::Finished) {
+		throw FTL_Error("Cannot call blend at this time");
+	} else if (stage_ == Stage::ReadySubmit) {
+		stage_ = Stage::Blending;
+		_endSubmit();
+	}
 
-	temp_.createTexture<int>(Channel::Contribution);
+	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
 
-	sets_.clear();
+	auto &buf = colouriser_->colourise(*out_, c, stream_);
+	//cv::cuda::addWeighted(buf.to_gpumat(), alpha, out_->get<GpuMat>(out_chan_), 1.0f-alpha, 0.0f,
+	//	out_->get<GpuMat>(out_chan_), -1, cvstream);
+
+	ftl::cuda::blend_alpha(buf, out_->getTexture<uchar4>(out_chan_), alpha, 1.0f-alpha, stream_);
 }
 
 void CUDARender::end() {
-	/*ftl::cuda::dibr_normalise(
-		temp_.getTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
-		output.createTexture<T>(out),
-		temp_.getTexture<float>(Channel::Contribution),
-		stream
-	);*/
+	if (stage_ == Stage::ReadySubmit) {
+		_endSubmit();
+	}
+
+	_end();
+	stage_ = Stage::Finished;
+}
 
+void CUDARender::_endSubmit() {
+	// Carry out all reprojections
 	for (auto &s : sets_) {
 		scene_ = s.fs;
 		try {
@@ -731,26 +526,29 @@ void CUDARender::end() {
 			LOG(ERROR) << "Exception in render: " << e.what();
 		}
 	}
+
 	scene_ = nullptr;
 
-	// FIXME: Allow for other channel accumulations
+	// Convert accumulated colour to BGRA 8bit
 	ftl::cuda::dibr_normalise(
-		temp_.getTexture<typename AccumSelector<uchar4>::type>(AccumSelector<uchar4>::channel),
-		out_->createTexture<uchar4>(Channel::Colour),
-		temp_.getTexture<int>(Channel::Contribution),
+		accum_,
+		out_->getTexture<uchar4>(out_chan_),
+		contrib_,
 		stream_
 	);
+}
 
+void CUDARender::_end() {
 	_postprocessColours(*out_);
 
 	cudaSafeCall(cudaStreamSynchronize(stream_));
 }
 
 bool CUDARender::submit(ftl::rgbd::FrameSet *in, Channels<0> chans, const Eigen::Matrix4d &t) {
-	if (scene_) {
-		LOG(WARNING) << "Already rendering...";
-		return false;
+	if (stage_ != Stage::ReadySubmit) {
+		throw FTL_Error("Renderer not ready for submits");
 	}
+
 	scene_ = in;
 	if (scene_->frames.size() == 0) {
 		scene_ = nullptr;
diff --git a/components/renderers/cpp/src/colour_cuda.hpp b/components/renderers/cpp/src/colour_cuda.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..fe499af68e956c4b8c9d2fd7bab2b87264cd2df0
--- /dev/null
+++ b/components/renderers/cpp/src/colour_cuda.hpp
@@ -0,0 +1,23 @@
+#ifndef _FTL_RENDER_COLOUR_CUDA_HPP_
+#define _FTL_RENDER_COLOUR_CUDA_HPP_
+
+#include <ftl/cuda_common.hpp>
+
+namespace ftl {
+namespace cuda {
+
+template <typename T>
+void lut(ftl::cuda::TextureObject<T> &in, ftl::cuda::TextureObject<uchar4> &out,
+		const cv::cuda::PtrStepSz<uchar3> &lut, float minval, float maxval,
+		bool invert, cudaStream_t stream);
+
+void blend_alpha(
+		ftl::cuda::TextureObject<uchar4> &in,
+		ftl::cuda::TextureObject<uchar4> &out,
+		float alpha, float beta,
+		cudaStream_t stream);
+
+}
+}
+
+#endif 
\ No newline at end of file
diff --git a/components/renderers/cpp/src/colour_util.cu b/components/renderers/cpp/src/colour_util.cu
new file mode 100644
index 0000000000000000000000000000000000000000..ae3d72f8cde48af1a615addd8782076a09e6ec3d
--- /dev/null
+++ b/components/renderers/cpp/src/colour_util.cu
@@ -0,0 +1,109 @@
+#include "colour_cuda.hpp"
+
+using ftl::cuda::TextureObject;
+
+__device__ inline uchar4 make_uchar4(const uchar3 &v, uchar v2) {
+	return make_uchar4(v.x, v.y, v.z, v2);
+}
+
+template <typename T, bool INVERT>
+ __global__ void lut_kernel(
+		const T* __restrict__ in,
+		int in_pitch, 
+		uchar4* __restrict__ out,
+		int out_pitch,
+		int width, int height,
+		const uchar3* __restrict__ lut,
+		float minval, float maxval) {
+
+	__shared__ uchar4 table[256];
+
+	int id = threadIdx.x + blockDim.x*threadIdx.y;
+	table[id] = make_uchar4(lut[id], (id == 0 || id == 255) ? 0 : 255);
+
+	__syncthreads();
+
+	const float t = (1.0f / (maxval - minval));
+
+	for (STRIDE_Y(y, height)) {
+	for (STRIDE_X(x, width)) {
+		const float i = __saturatef((float(in[x+y*in_pitch]) - minval) * t);
+		out[x+y*out_pitch] = table[uchar(((INVERT) ? 1.0f-i : i)*255.0f)];
+	}
+	}
+}
+
+template <typename T>
+void ftl::cuda::lut(TextureObject<T> &in, TextureObject<uchar4> &out,
+		const cv::cuda::PtrStepSz<uchar3> &lut, float minval, float maxval,
+		bool invert,
+		cudaStream_t stream) {
+
+	static constexpr int THREADS_X = 64;  // Must total 256
+	static constexpr int THREADS_Y = 4;
+
+	const dim3 gridSize(6,64);
+    const dim3 blockSize(THREADS_X, THREADS_Y);
+
+	if (invert) {
+		lut_kernel<T,true><<<gridSize, blockSize, 0, stream>>>(in.devicePtr(), in.pixelPitch(), out.devicePtr(), out.pixelPitch(), out.width(), out.height(), lut.data, minval, maxval);
+	} else {
+		lut_kernel<T,false><<<gridSize, blockSize, 0, stream>>>(in.devicePtr(), in.pixelPitch(), out.devicePtr(), out.pixelPitch(), out.width(), out.height(), lut.data, minval, maxval);
+	}
+	cudaSafeCall( cudaGetLastError() );
+}
+
+template void ftl::cuda::lut<float>(TextureObject<float> &in, TextureObject<uchar4> &out,
+	const cv::cuda::PtrStepSz<uchar3> &lut, float minval, float maxval, bool invert,
+	cudaStream_t stream);
+
+template void ftl::cuda::lut<short>(TextureObject<short> &in, TextureObject<uchar4> &out,
+	const cv::cuda::PtrStepSz<uchar3> &lut, float minval, float maxval, bool invert,
+	cudaStream_t stream);
+
+// ==== Blending ===============================================================
+
+__global__ void blend_alpha_kernel(
+		const uchar4* __restrict__ in,
+		int in_pitch, 
+		uchar4* __restrict__ out,
+		int out_pitch,
+		int width, int height,
+		float alpha) {
+
+	for (STRIDE_Y(y, height)) {
+	for (STRIDE_X(x, width)) {
+		const uchar4 c1 = in[x+y*in_pitch];
+		const uchar4 c2 = out[x+y*out_pitch];
+
+		const float a = alpha*(float(c1.w)/255.0f);
+		const float b = 1.0f - a;
+
+		out[x+y*out_pitch] = make_uchar4(
+			float(c1.x)*a + float(c2.x)*b,
+			float(c1.y)*a + float(c2.y)*b,
+			float(c1.z)*a + float(c2.z)*b,
+			255.0f
+		);
+	}
+	}
+}
+
+void ftl::cuda::blend_alpha(
+		TextureObject<uchar4> &in,
+		TextureObject<uchar4> &out,
+		float alpha, float beta,
+		cudaStream_t stream) {
+
+	static constexpr int THREADS_X = 32;
+	static constexpr int THREADS_Y = 8;
+
+	const dim3 gridSize(6,64);
+	const dim3 blockSize(THREADS_X, THREADS_Y);
+
+	blend_alpha_kernel<<<gridSize, blockSize, 0, stream>>>(
+		in.devicePtr(), in.pixelPitch(),
+		out.devicePtr(), out.pixelPitch(),
+		out.width(), out.height(), alpha);
+	cudaSafeCall( cudaGetLastError() );
+}
diff --git a/components/renderers/cpp/src/colouriser.cpp b/components/renderers/cpp/src/colouriser.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..70521ba4104d6d457ab1e502170fbb22b740a60a
--- /dev/null
+++ b/components/renderers/cpp/src/colouriser.cpp
@@ -0,0 +1,206 @@
+#include <ftl/render/colouriser.hpp>
+#include "splatter_cuda.hpp"
+#include "colour_cuda.hpp"
+#include <ftl/cuda/normals.hpp>
+
+#include <opencv2/cudaarithm.hpp>
+#include <opencv2/cudaimgproc.hpp>
+
+#include <string>
+
+using ftl::render::Colouriser;
+using ftl::cuda::TextureObject;
+using ftl::codecs::Channel;
+using cv::cuda::GpuMat;
+using std::stoul;
+
+static cv::cuda::GpuMat depth_lut;
+
+#include "turbo_map.hpp"
+
+/*
+ * Parse a CSS style colour string into a scalar.
+ */
+cv::Scalar ftl::render::parseCVColour(const std::string &colour) {
+	std::string c = colour;
+	if (c[0] == '#') {
+		c.erase(0, 1);
+		unsigned long value = stoul(c.c_str(), nullptr, 16);
+		return cv::Scalar(
+			(value >> 0) & 0xff,
+			(value >> 8) & 0xff,
+			(value >> 16) & 0xff,
+			(value >> 24) & 0xff
+		);
+	}
+
+	return cv::Scalar(0,0,0,0);
+}
+
+/*
+ * Parse a CSS style colour string into a scalar.
+ */
+uchar4 ftl::render::parseCUDAColour(const std::string &colour) {
+	std::string c = colour;
+	if (c[0] == '#') {
+		c.erase(0, 1);
+		unsigned long value = stoul(c.c_str(), nullptr, 16);
+		return make_uchar4(
+			(value >> 0) & 0xff,
+			(value >> 8) & 0xff,
+			(value >> 16) & 0xff,
+			(value >> 24) & 0xff
+		);
+	}
+
+	return make_uchar4(0,0,0,0);
+}
+
+/*
+ * H(Hue): 0 - 360 degree (integer)
+ * S(Saturation): 0 - 1.00 (double)
+ * V(Value): 0 - 1.00 (double)
+ * 
+ * output[3]: Output, array size 3, int
+ */
+static cv::Scalar HSVtoRGB(int H, double S, double V) {
+	double C = S * V;
+	double X = C * (1 - abs(fmod(H / 60.0, 2) - 1));
+	double m = V - C;
+	double Rs, Gs, Bs;
+
+	if(H >= 0 && H < 60) {
+		Rs = C;
+		Gs = X;
+		Bs = 0;	
+	}
+	else if(H >= 60 && H < 120) {	
+		Rs = X;
+		Gs = C;
+		Bs = 0;	
+	}
+	else if(H >= 120 && H < 180) {
+		Rs = 0;
+		Gs = C;
+		Bs = X;	
+	}
+	else if(H >= 180 && H < 240) {
+		Rs = 0;
+		Gs = X;
+		Bs = C;	
+	}
+	else if(H >= 240 && H < 300) {
+		Rs = X;
+		Gs = 0;
+		Bs = C;	
+	}
+	else {
+		Rs = C;
+		Gs = 0;
+		Bs = X;	
+	}
+
+	return cv::Scalar((Bs + m) * 255, (Gs + m) * 255, (Rs + m) * 255, 0);
+}
+
+
+Colouriser::Colouriser(nlohmann::json &config) : ftl::Configurable(config) {
+
+}
+
+Colouriser::~Colouriser() {
+
+}
+
+TextureObject<uchar4> &Colouriser::colourise(ftl::rgbd::Frame &f, Channel c, cudaStream_t stream) {
+	switch (c) {
+	case Channel::ColourHighRes	:
+	case Channel::Colour		:
+	case Channel::Colour2		: return _processColour(f,c,stream);
+	case Channel::Depth			:
+	case Channel::Depth2		: return _processFloat(f,c, value("depth_min", f.getLeft().minDepth), value("depth_max", f.getLeft().maxDepth), stream);
+	case Channel::Normals		:
+	case Channel::Normals2		: return _processNormals(f, c, stream);
+	case Channel::Weights		: return _processSingle<short>(f, c, stream);
+	default: throw FTL_Error("Cannot colourise channel " << (int)c);
+	}
+}
+
+TextureObject<uchar4> &Colouriser::_processNormals(ftl::rgbd::Frame &f, Channel c, cudaStream_t stream) {
+	cv::Size size = f.get<cv::cuda::GpuMat>(c).size();
+	auto &buf = _getBuffer(size.width, size.height);
+
+	auto light_diffuse = parseCUDAColour(value("diffuse", std::string("#e0e0e0")));
+	auto light_ambient = parseCUDAColour(value("ambient", std::string("#0e0e0e")));
+	auto light_pos = make_float3(value("light_x", 0.3f), value("light_y", 0.2f), value("light_z", 1.0f));
+
+	ftl::cuda::normal_visualise(f.createTexture<half4>(c), buf,
+			light_pos,
+			light_diffuse,
+			light_ambient, stream);
+	return buf;
+}
+
+template <typename T>
+TextureObject<uchar4> &Colouriser::_processSingle(ftl::rgbd::Frame &f, Channel c, cudaStream_t stream) {
+	cv::Size size = f.get<cv::cuda::GpuMat>(c).size();
+	auto &buf = _getBuffer(size.width, size.height);
+
+	if (depth_lut.empty()) {
+		cv::Mat lut(1,256, CV_8UC3, turbo_map);
+		depth_lut.upload(lut);
+	}
+
+	ftl::cuda::lut(f.createTexture<T>(c), buf, depth_lut, 0, std::numeric_limits<T>::max(), true, stream);
+	return buf;
+}
+
+TextureObject<uchar4> &Colouriser::_processFloat(ftl::rgbd::Frame &f, Channel c, float minval, float maxval, cudaStream_t stream) {
+	cv::Size size = f.get<cv::cuda::GpuMat>(c).size();
+	auto &buf = _getBuffer(size.width, size.height);
+
+	if (depth_lut.empty()) {
+		cv::Mat lut(1,256, CV_8UC3, turbo_map);
+		depth_lut.upload(lut);
+	}
+
+	ftl::cuda::lut(f.createTexture<float>(c), buf, depth_lut, minval, maxval, false, stream);
+	return buf;
+}
+
+TextureObject<uchar4> &Colouriser::_processColour(ftl::rgbd::Frame &f, Channel c, cudaStream_t stream) {
+	uint8_t show_mask = value("show_mask", 0);
+	bool colour_sources = value("colour_sources", false);
+
+	if (!colour_sources && show_mask == 0) {
+		return f.createTexture<uchar4>(c);
+	}
+
+	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
+
+	cv::Size size = f.get<cv::cuda::GpuMat>(c).size();
+	auto &buf = _getBuffer(size.width, size.height);
+
+	if (colour_sources) {
+		auto colour = HSVtoRGB(360 / 8 * f.id, 0.6, 0.85);
+		buf.to_gpumat().setTo(colour, cvstream);
+	}
+
+	// FIXME: This doesn't work with the buffer yet.
+	if (f.hasChannel(Channel::Mask)) {
+		if (show_mask > 0) {
+			ftl::cuda::show_mask(f.getTexture<uchar4>(c), f.getTexture<uint8_t>(Channel::Mask), show_mask, make_uchar4(255,0,255,255), stream);
+		}
+	}
+
+	return buf;
+}
+
+TextureObject<uchar4> &Colouriser::_getBuffer(size_t width, size_t height) {
+	for (auto *b : textures_) {
+		if (b->width() == width && b->height() == height) return *b;
+	}
+	auto *nb = new ftl::cuda::TextureObject<uchar4>(width, height, true);
+	textures_.push_back(nb);
+	return *nb;
+}
diff --git a/components/renderers/cpp/src/normals.cu b/components/renderers/cpp/src/normals.cu
index 81ee7638b2df2cb3193dacdcfb679564818dc4bb..1375dc0356fb682c7e0990a90b21255fa83c2f3a 100644
--- a/components/renderers/cpp/src/normals.cu
+++ b/components/renderers/cpp/src/normals.cu
@@ -415,21 +415,24 @@ __global__ void vis_normals_kernel(ftl::cuda::TextureObject<half4> norm,
     const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
     const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
 
-    if(x >= norm.width() || y >= norm.height()) return;
-
-    output(x,y) = make_uchar4(0,0,0,0);
-    float3 ray = direction;
-    ray = ray / length(ray);
-    float3 n = make_float3(norm.tex2D((int)x,(int)y));
-    float l = length(n);
-    if (l == 0) return;
-    n /= l;
-
-    const float d = max(dot(ray, n), 0.0f);
-    output(x,y) = make_uchar4(
-		min(255.0f, diffuse.x*d + ambient.x),
-		min(255.0f, diffuse.y*d + ambient.y),
-		min(255.0f, diffuse.z*d + ambient.z), 255);
+    if(x < norm.width() && y < norm.height()) {
+		output(x,y) = make_uchar4(ambient.x,ambient.y,ambient.z,0);
+
+		float3 ray = direction;
+		ray = ray / length(ray);
+		float3 n = make_float3(norm.tex2D((int)x,(int)y));
+		float l = length(n);
+
+		if (l != 0) {
+			n /= l;
+
+			const float d = max(dot(ray, n), 0.0f);
+			output(x,y) = make_uchar4(
+				min(255.0f, diffuse.x*d + ambient.x),
+				min(255.0f, diffuse.y*d + ambient.y),
+				min(255.0f, diffuse.z*d + ambient.z), 255);
+		}
+	}
 }
 
 void ftl::cuda::normal_visualise(ftl::cuda::TextureObject<half4> &norm,
diff --git a/components/renderers/cpp/src/turbo_map.hpp b/components/renderers/cpp/src/turbo_map.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..e44d9ffb76683c9a963cf2911da336b58889dfdf
--- /dev/null
+++ b/components/renderers/cpp/src/turbo_map.hpp
@@ -0,0 +1 @@
+static unsigned char turbo_map[256][3] = {{48,18,59},{50,21,67},{51,24,74},{52,27,81},{53,30,88},{54,33,95},{55,36,102},{56,39,109},{57,42,115},{58,45,121},{59,47,128},{60,50,134},{61,53,139},{62,56,145},{63,59,151},{63,62,156},{64,64,162},{65,67,167},{65,70,172},{66,73,177},{66,75,181},{67,78,186},{68,81,191},{68,84,195},{68,86,199},{69,89,203},{69,92,207},{69,94,211},{70,97,214},{70,100,218},{70,102,221},{70,105,224},{70,107,227},{71,110,230},{71,113,233},{71,115,235},{71,118,238},{71,120,240},{71,123,242},{70,125,244},{70,128,246},{70,130,248},{70,133,250},{70,135,251},{69,138,252},{69,140,253},{68,143,254},{67,145,254},{66,148,255},{65,150,255},{64,153,255},{62,155,254},{61,158,254},{59,160,253},{58,163,252},{56,165,251},{55,168,250},{53,171,248},{51,173,247},{49,175,245},{47,178,244},{46,180,242},{44,183,240},{42,185,238},{40,188,235},{39,190,233},{37,192,231},{35,195,228},{34,197,226},{32,199,223},{31,201,221},{30,203,218},{28,205,216},{27,208,213},{26,210,210},{26,212,208},{25,213,205},{24,215,202},{24,217,200},{24,219,197},{24,221,194},{24,222,192},{24,224,189},{25,226,187},{25,227,185},{26,228,182},{28,230,180},{29,231,178},{31,233,175},{32,234,172},{34,235,170},{37,236,167},{39,238,164},{42,239,161},{44,240,158},{47,241,155},{50,242,152},{53,243,148},{56,244,145},{60,245,142},{63,246,138},{67,247,135},{70,248,132},{74,248,128},{78,249,125},{82,250,122},{85,250,118},{89,251,115},{93,252,111},{97,252,108},{101,253,105},{105,253,102},{109,254,98},{113,254,95},{117,254,92},{121,254,89},{125,255,86},{128,255,83},{132,255,81},{136,255,78},{139,255,75},{143,255,73},{146,255,71},{150,254,68},{153,254,66},{156,254,64},{159,253,63},{161,253,61},{164,252,60},{167,252,58},{169,251,57},{172,251,56},{175,250,55},{177,249,54},{180,248,54},{183,247,53},{185,246,53},{188,245,52},{190,244,52},{193,243,52},{195,241,52},{198,240,52},{200,239,52},{203,237,52},{205,236,52},{208,234,52},{210,233,53},{212,231,53},{215,229,53},{217,228,54},{219,226,54},{221,224,55},{223,223,55},{225,221,55},{227,219,56},{229,217,56},{231,215,57},{233,213,57},{235,211,57},{236,209,58},{238,207,58},{239,205,58},{241,203,58},{242,201,58},{244,199,58},{245,197,58},{246,195,58},{247,193,58},{248,190,57},{249,188,57},{250,186,57},{251,184,56},{251,182,55},{252,179,54},{252,177,54},{253,174,53},{253,172,52},{254,169,51},{254,167,50},{254,164,49},{254,161,48},{254,158,47},{254,155,45},{254,153,44},{254,150,43},{254,147,42},{254,144,41},{253,141,39},{253,138,38},{252,135,37},{252,132,35},{251,129,34},{251,126,33},{250,123,31},{249,120,30},{249,117,29},{248,114,28},{247,111,26},{246,108,25},{245,105,24},{244,102,23},{243,99,21},{242,96,20},{241,93,19},{240,91,18},{239,88,17},{237,85,16},{236,83,15},{235,80,14},{234,78,13},{232,75,12},{231,73,12},{229,71,11},{228,69,10},{226,67,10},{225,65,9},{223,63,8},{221,61,8},{220,59,7},{218,57,7},{216,55,6},{214,53,6},{212,51,5},{210,49,5},{208,47,5},{206,45,4},{204,43,4},{202,42,4},{200,40,3},{197,38,3},{195,37,3},{193,35,2},{190,33,2},{188,32,2},{185,30,2},{183,29,2},{180,27,1},{178,26,1},{175,24,1},{172,23,1},{169,22,1},{167,20,1},{164,19,1},{161,18,1},{158,16,1},{155,15,1},{152,14,1},{149,13,1},{146,11,1},{142,10,1},{139,9,2},{136,8,2},{133,7,2},{129,6,2},{126,5,2},{122,4,3}};
\ No newline at end of file
diff --git a/components/rgbd-sources/src/frameset.cpp b/components/rgbd-sources/src/frameset.cpp
index acf9e1c2f91dad2fab01b4f29281cb1f42058898..b14749fb60db736861c2d5ec2a46d466bfc3f508 100644
--- a/components/rgbd-sources/src/frameset.cpp
+++ b/components/rgbd-sources/src/frameset.cpp
@@ -128,6 +128,7 @@ ftl::rgbd::Frame &Builder::get(int64_t timestamp, size_t ix) {
 
 	//frame.swapTo(ftl::codecs::kAllChannels, fs->frames[ix]);
 
+	fs->frames[ix].id = ix;
 	return fs->frames[ix];
 }
 
diff --git a/components/structures/include/ftl/data/frame.hpp b/components/structures/include/ftl/data/frame.hpp
index 612b459b7872a4737b76013e28d84acb5d8cccee..74c52d20731b25923ea87fbdd15d36d89a3a48fb 100644
--- a/components/structures/include/ftl/data/frame.hpp
+++ b/components/structures/include/ftl/data/frame.hpp
@@ -268,6 +268,8 @@ public:
 
 	typedef STATE State;
 
+	int id;
+
 protected:
 	/* Lookup internal state for a given channel. */
 	inline DATA &getData(ftl::codecs::Channel c) { return data_[static_cast<unsigned int>(c)-BASE]; }