diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp
index e33ec641ca9b8a0b90340bad56088e524aa03e90..2332831501d36c3578973a341ea924e8a48cd06b 100644
--- a/applications/gui/src/camera.cpp
+++ b/applications/gui/src/camera.cpp
@@ -9,6 +9,7 @@
 #include <opencv2/imgcodecs.hpp>
 
 #include <ftl/operators/antialiasing.hpp>
+#include <ftl/cuda/normals.hpp>
 
 #include <ftl/codecs/faces.hpp>
 
@@ -359,6 +360,7 @@ 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_);
 
 	if (screen_->root()->value("show_poses", false)) {
@@ -418,6 +420,34 @@ void ftl::gui::Camera::_downloadFrames(ftl::rgbd::Frame *frame) {
 		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<float4>(Channel::Normals, ftl::rgbd::Format<float4>(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<float4>(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);
+	}
+}
+
+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;
+		}
 	}
 }
 
@@ -639,6 +669,7 @@ cv::Mat ftl::gui::Camera::visualizeActiveChannel() {
 			visualizeDepthMap(im2_, result, 7.0);
 			if (screen_->root()->value("showEdgesInDepth", false)) drawEdges(im1_, result);
 			break;
+		case Channel::ColourNormals:
 		case Channel::Right:
 			result = im2_;
 			break;
diff --git a/applications/gui/src/camera.hpp b/applications/gui/src/camera.hpp
index fd4f91d5aafcd928c977613241e7b20eb7a067db..361ee439bb5d612a061d925e07d600f1c5da83c1 100644
--- a/applications/gui/src/camera.hpp
+++ b/applications/gui/src/camera.hpp
@@ -62,7 +62,7 @@ class Camera {
 	/**
 	 * Update the available channels.
 	 */
-	void update(const ftl::codecs::Channels<0> &c) { channels_ = (isVirtual()) ? c + ftl::codecs::Channel::Right : c; }
+	void update(int fsid, const ftl::codecs::Channels<0> &c);
 
 	void draw(std::vector<ftl::rgbd::FrameSet*> &fss);
 
diff --git a/applications/gui/src/src_window.cpp b/applications/gui/src/src_window.cpp
index cce1942e0c9556b68108533f0fb2dac9419579e9..328e29ad6b278fdbc7e676f18cb5b29538427673 100644
--- a/applications/gui/src/src_window.cpp
+++ b/applications/gui/src/src_window.cpp
@@ -209,8 +209,8 @@ bool SourceWindow::_processFrameset(ftl::rgbd::FrameSet &fs, bool fromstream) {
 		if (screen_->activeCamera() == cam.second.camera ||
 			(screen_->activeCamera() == nullptr && cycle_ % cameras_.size() == i++))  cam.second.camera->update(framesets_);
 
-		if (fromstream) cam.second.camera->update(cstream->available(fs.id));
-		else if (fs.frames.size() > 0) cam.second.camera->update(fs.frames[0].getChannels());
+		if (fromstream) cam.second.camera->update(fs.id, cstream->available(fs.id));
+		else if (fs.frames.size() > 0) cam.second.camera->update(fs.id, fs.frames[0].getChannels());
 	}
 	++cycle_;
 
@@ -220,10 +220,10 @@ 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");
-		//pre_pipeline_->append<ftl::operators::HFSmoother>("hfnoise");
 		//pre_pipeline_->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);
+		//p->append<ftl::operators::HFSmoother>("hfnoise");
 		p->append<ftl::operators::CrossSupport>("cross");
 		p->append<ftl::operators::DiscontinuityMask>("discontinuity");
 		p->append<ftl::operators::CullDiscontinuity>("remove_discontinuity");
diff --git a/components/common/cpp/include/ftl/cuda_common.hpp b/components/common/cpp/include/ftl/cuda_common.hpp
index a7041360925d36bd94355554edd5c1b64fa9b30a..4741d99d0af4ab20fe73878cb7b5787ef1c7c28f 100644
--- a/components/common/cpp/include/ftl/cuda_common.hpp
+++ b/components/common/cpp/include/ftl/cuda_common.hpp
@@ -40,12 +40,14 @@ template <> struct Float<float> { typedef float type; };
 template <> struct Float<int> { typedef float type; };
 template <> struct Float<float4> { typedef float4 type; };
 template <> struct Float<uchar4> { typedef float4 type; };
+template <> struct Float<uint8_t> { typedef float type; };
 template <> struct Float<short2> { typedef float2 type; };
 
 template <typename T>
 struct ScaleValue;
 
 template <> struct ScaleValue<uchar4> { static constexpr float value = 255.0f; };
+template <> struct ScaleValue<uint8_t> { static constexpr float value = 255.0f; };
 template <> struct ScaleValue<float> { static constexpr float value = 1.0f; };
 template <> struct ScaleValue<float4> { static constexpr float value = 1.0f; };
 
diff --git a/components/operators/src/mask_cuda.hpp b/components/operators/include/ftl/operators/mask_cuda.hpp
similarity index 50%
rename from components/operators/src/mask_cuda.hpp
rename to components/operators/include/ftl/operators/mask_cuda.hpp
index 20c266290f10ce6aca19af3cfe45a9d3f7c03355..818724b16da48f44d0177749b41fee0a5634e68f 100644
--- a/components/operators/src/mask_cuda.hpp
+++ b/components/operators/include/ftl/operators/mask_cuda.hpp
@@ -8,51 +8,70 @@ namespace ftl {
 namespace cuda {
 
 /**
- * Wrap an int mask value used to flag individual depth pixels.
+ * Wrap an int mask value used to flag individual depth pixels. This acts like
+ * a stencil buffer.
  */
 class Mask {
 	public:
-	__device__ inline Mask() : v_(0) {}
-	__device__ explicit inline Mask(int v) : v_(v) {}
+	__device__ inline Mask() : v_(0u) {}
+	__device__ explicit inline Mask(uint8_t v) : v_(v) {}
 	#ifdef __CUDACC__
-	__device__ inline Mask(const ftl::cuda::TextureObject<int> &m, int x, int y) : v_(m.tex2D(x,y)) {}
+	__device__ inline Mask(const ftl::cuda::TextureObject<uint8_t> &m, int x, int y) : v_(m.tex2D(x,y)) {}
 	#endif
 	__device__ inline operator int() const { return v_; }
 
-	__device__ inline bool is(int m) const { return v_ & m; }
+    __device__ inline bool is(uint8_t m) const { return v_ & m; }
 
 	__device__ inline bool isFilled() const { return v_ & kMask_Filled; }
 	__device__ inline bool isDiscontinuity() const { return v_ & kMask_Discontinuity; }
 	__device__ inline bool hasCorrespondence() const { return v_ & kMask_Correspondence; }
 	__device__ inline bool isBad() const { return v_ & kMask_Bad; }
+	__device__ inline bool isNoise() const { return v_ & kMask_Noise; }
 
 	__device__ inline void isFilled(bool v) { v_ = (v) ? v_ | kMask_Filled : v_ & (~kMask_Filled); }
 	__device__ inline void isDiscontinuity(bool v) { v_ = (v) ? v_ | kMask_Discontinuity : v_ & (~kMask_Discontinuity); }
 	__device__ inline void hasCorrespondence(bool v) { v_ = (v) ? v_ | kMask_Correspondence : v_ & (~kMask_Correspondence); }
 	__device__ inline void isBad(bool v) { v_ = (v) ? v_ | kMask_Bad : v_ & (~kMask_Bad); }
+	__device__ inline void isNoise(bool v) { v_ = (v) ? v_ | kMask_Noise : v_ & (~kMask_Noise); }
 
-	static constexpr int kMask_Filled = 0x0001;
-	static constexpr int kMask_Discontinuity = 0x0002;
-	static constexpr int kMask_Correspondence = 0x0004;
-	static constexpr int kMask_Bad = 0x0008;
+    static constexpr uint8_t kMask_Filled = 0x01;
+	static constexpr uint8_t kMask_Discontinuity = 0x02;
+	static constexpr uint8_t kMask_Correspondence = 0x04;
+	static constexpr uint8_t kMask_Bad = 0x08;
+	static constexpr uint8_t kMask_Noise = 0x10;
 
 	private:
-	int v_;
+	uint8_t v_;
 };
 
 void discontinuity(
-		ftl::cuda::TextureObject<int> &mask,
+		ftl::cuda::TextureObject<uint8_t> &mask,
 		ftl::cuda::TextureObject<uchar4> &support,
 		ftl::cuda::TextureObject<float> &depth,
 		const cv::Size size,
 		const double minDepth,
 		const double maxDepth,
-		int radius, float threshold,
+		int radius, float depthCoef,
 		cudaStream_t stream);
 
-void cull_discontinuity(
-		ftl::cuda::TextureObject<int> &mask,
+void discontinuity(
+		ftl::cuda::TextureObject<uint8_t> &mask,
+		ftl::cuda::TextureObject<uchar4> &support,
+		ftl::cuda::TextureObject<float> &depth,
+		const cv::Size size,
+		const double minDepth,
+		const double maxDepth,
+		float depthCoef,
+		float discon_thresh,
+		float noise_thresh,
+		float area_max,
+		cudaStream_t stream);
+
+void cull_mask(
+		ftl::cuda::TextureObject<uint8_t> &mask,
 		ftl::cuda::TextureObject<float> &depth,
+		uint8_t id,
+		unsigned int radius,
 		cudaStream_t stream);
 
 }
diff --git a/components/operators/include/ftl/operators/normals.hpp b/components/operators/include/ftl/operators/normals.hpp
index a46d2ff43449deebd2f9a12a87ebebdc2bb3a231..494a0d10d5ab63ed47902b0b7311a71cd01d4a87 100644
--- a/components/operators/include/ftl/operators/normals.hpp
+++ b/components/operators/include/ftl/operators/normals.hpp
@@ -21,6 +21,23 @@ class Normals : public ftl::operators::Operator {
 
 };
 
+/**
+ * Calculate the dot product of the normal and a camera ray. Outputs a single
+ * float value between 1 and -1 with 1 being facing camera, 0 being
+ * perpendicular and -1 facing wrong direction. Useful during rendering where
+ * full normals are not required.
+ */
+class NormalDot : public ftl::operators::Operator {
+	public:
+    explicit NormalDot(ftl::Configurable*);
+    ~NormalDot();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t stream) override;
+
+};
+
 /**
  * Calculate rough normals from local depth gradients and perform a weighted
  * smoothing over the neighbourhood.
diff --git a/components/operators/src/correspondence.cu b/components/operators/src/correspondence.cu
index 05d60106059df6855b65003af076bb751176e56f..edc333c759221e43247af69748e918aa24f0657a 100644
--- a/components/operators/src/correspondence.cu
+++ b/components/operators/src/correspondence.cu
@@ -1,6 +1,6 @@
 #include "mvmls_cuda.hpp"
 #include <ftl/cuda/weighting.hpp>
-#include <ftl/cuda/mask.hpp>
+#include <ftl/operators/mask_cuda.hpp>
 #include <ftl/cuda/warp.hpp>
 
 using ftl::cuda::TextureObject;
@@ -101,7 +101,7 @@ __global__ void corresponding_point_kernel(
         TextureObject<uchar4> c2,
         TextureObject<short2> screenOut,
 		TextureObject<float> conf,
-		TextureObject<int> mask,
+		TextureObject<uint8_t> mask,
         float4x4 pose,
         Camera cam1,
         Camera cam2, ftl::cuda::MvMLSParams params) {
@@ -148,7 +148,10 @@ __global__ void corresponding_point_kernel(
         linePos.x = lineOrigin.x - ((COR_STEPS/2));
         linePos.y = lineOrigin.y - (((COR_STEPS/2)) * lineM);
 		//float depthPos = depth1 - (float((COR_STEPS/2)) * depthM);
-        float depthPos2 = camPosOrigin.z - (float((COR_STEPS/2)) * depthM2);
+		float depthPos2 = camPosOrigin.z - (float((COR_STEPS/2)) * depthM2);
+		//const float depthCoef = cam1.baseline*cam1.fx;
+
+		const float depthCoef = (1.0f / cam1.fx) * 10.0f;
         
         uint badMask = 0;
         int bestStep = COR_STEPS/2;
@@ -180,7 +183,13 @@ __global__ void corresponding_point_kernel(
 				) ? 1 << i : 0;
 			
 			//if (FUNCTION == 1) {
-			float weight = ftl::cuda::weighting(fabs(depth2 - depthPos2), cweight*params.spatial_smooth);
+			// TODO: Spatial smooth must be disparity discon threshold of largest depth in original camera space.
+			// ie. if depth1 > depth2 then depth1 has the largest error potential and the resolution at that
+			// depth is used to determine the spatial smoothing amount.
+	
+			const float maxdepth = max(depth1, depth2);
+			const float smooth = depthCoef * maxdepth;
+			float weight = ftl::cuda::weighting(fabs(depth2 - depthPos2), cweight*smooth);
 			//weight = ftl::cuda::halfWarpSum(weight);
 			//} else {
 			//	const float dweight = ftl::cuda::weighting(fabs(depth2 - depthPos2), params.spatial_smooth);
@@ -243,7 +252,7 @@ void ftl::cuda::correspondence(
         TextureObject<uchar4> &c2,
         TextureObject<short2> &screen,
 		TextureObject<float> &conf,
-		TextureObject<int> &mask,
+		TextureObject<uint8_t> &mask,
         float4x4 &pose2,
         const Camera &cam1,
         const Camera &cam2, const MvMLSParams &params, int func,
diff --git a/components/operators/src/mask.cpp b/components/operators/src/mask.cpp
index ac56ba2ad9181324cec41e70067a4e6b7b22880e..302b1b39555401cc4bf83091a44def76d91fa6ab 100644
--- a/components/operators/src/mask.cpp
+++ b/components/operators/src/mask.cpp
@@ -1,5 +1,5 @@
 #include <ftl/operators/mask.hpp>
-#include "mask_cuda.hpp"
+#include <ftl/operators/mask_cuda.hpp>
 
 using ftl::operators::DiscontinuityMask;
 using ftl::operators::CullDiscontinuity;
@@ -17,18 +17,31 @@ DiscontinuityMask::~DiscontinuityMask() {
 bool DiscontinuityMask::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t stream) {
 	if (in.hasChannel(Channel::Mask)) return true;
 	
-	int radius = config()->value("radius", 2);
-	float threshold = config()->value("threshold", 0.1f);
+	//int radius = config()->value("radius", 2);
+	float disconPixels = config()->value("discon_pixels", 15.0f);
+	float depthCoef = (1.0f / in.getLeft().fx) * disconPixels;
+	float disconThresh = config()->value("discon_thresh", 0.8f);
+	float noiseThresh = config()->value("noise_thresh", 0.8f);
+	float areaMax = config()->value("area_max", 26.0f);  // Cross support radius squared + 1
 
 	if (!in.hasChannel(Channel::Depth) || !in.hasChannel(Channel::Support1)) return false;
 
+	/*ftl::cuda::discontinuity(
+		out.createTexture<uint8_t>(Channel::Mask, ftl::rgbd::Format<uint8_t>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+		in.createTexture<uchar4>(Channel::Support1),
+		in.createTexture<float>(Channel::Depth),
+		in.get<cv::cuda::GpuMat>(Channel::Depth).size(),
+		in.getLeftCamera().minDepth, in.getLeftCamera().maxDepth,
+		radius, depthCoef, stream
+	);*/
+
 	ftl::cuda::discontinuity(
-		out.createTexture<int>(Channel::Mask, ftl::rgbd::Format<int>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+		out.createTexture<uint8_t>(Channel::Mask, ftl::rgbd::Format<uint8_t>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
 		in.createTexture<uchar4>(Channel::Support1),
 		in.createTexture<float>(Channel::Depth),
 		in.get<cv::cuda::GpuMat>(Channel::Depth).size(),
 		in.getLeftCamera().minDepth, in.getLeftCamera().maxDepth,
-		radius, threshold, stream
+		depthCoef, disconThresh, noiseThresh, areaMax, stream
 	);
 
 	return true;
@@ -46,11 +59,16 @@ CullDiscontinuity::~CullDiscontinuity() {
 
 bool CullDiscontinuity::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t stream) {
 	if (!in.hasChannel(Channel::Depth) || !in.hasChannel(Channel::Mask)) return false;
+
+	uint8_t maskID = config()->value("mask_id", (unsigned int)ftl::cuda::Mask::kMask_Discontinuity);
+	unsigned int radius = config()->value("radius", 2);
 	
 	out.clearPackets(Channel::Depth);  // Force reset
-	ftl::cuda::cull_discontinuity(
-		in.createTexture<int>(Channel::Mask),
+	ftl::cuda::cull_mask(
+		in.createTexture<uint8_t>(Channel::Mask),
 		out.createTexture<float>(Channel::Depth),
+		maskID,
+		radius,
 		stream
 	);
 
diff --git a/components/operators/src/mask.cu b/components/operators/src/mask.cu
index 84011d897d065b9e42968dc0d531b95c789686d0..e030c87fab26dfdaf8297f7dc753d433ffcb6258 100644
--- a/components/operators/src/mask.cu
+++ b/components/operators/src/mask.cu
@@ -1,14 +1,15 @@
-#include "mask_cuda.hpp"
+#include <ftl/operators/mask_cuda.hpp>
 
 #define T_PER_BLOCK 8
 
 using ftl::cuda::Mask;
 
-__global__ void discontinuity_kernel(ftl::cuda::TextureObject<int> mask_out,
+/* OLD VERSION */
+__global__ void discontinuity_kernel(ftl::cuda::TextureObject<uint8_t> mask_out,
 										ftl::cuda::TextureObject<uchar4> support,
 										ftl::cuda::TextureObject<float> depth, 
 										const cv::Size size, const double minDepth, const double maxDepth,
-										float threshold, int radius) {
+										float depthCoef, int radius) {
 	
 	const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
 	const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
@@ -17,8 +18,11 @@ __global__ void discontinuity_kernel(ftl::cuda::TextureObject<int> mask_out,
 		Mask mask(0);
 
 		const float d = depth.tex2D((int)x, (int)y);
+		// Multiples of pixel size at given depth
+		//const float threshold = (depthCoef / ((depthCoef / d) - (radius+disconDisparities-1))) - d;
+		const float threshold = depthCoef * d;  // Where depthCoef = 1 / focal * N, N = number of pixel distances equal to a discon.
 
-		if (d >= minDepth && d <= maxDepth) {
+		if (d > minDepth && d < maxDepth) {
 			/* Orts-Escolano S. et al. 2016. Holoportation: Virtual 3D teleportation in real-time. */
 
 			// If colour cross support region terminates within the requested
@@ -42,21 +46,69 @@ __global__ void discontinuity_kernel(ftl::cuda::TextureObject<int> mask_out,
 				float dS = depth.tex2D((int)x, (int)y + sup.w + radius);
 				if (fabs(dS - d) > threshold) mask.isDiscontinuity(true);
 			}
+
+			// FIXME: The above results in a cross formation, need to test all 8 directions
 		}
 		
 		mask_out(x,y) = (int)mask;
 	}
 }
 
-void ftl::cuda::discontinuity(	ftl::cuda::TextureObject<int> &mask_out, ftl::cuda::TextureObject<uchar4> &support,
+/* New / Current version */
+__global__ void discontinuity_kernel(ftl::cuda::TextureObject<uint8_t> mask_out,
+		ftl::cuda::TextureObject<uchar4> support,
+		ftl::cuda::TextureObject<float> depth, 
+		const cv::Size size, const double minDepth, const double maxDepth,
+		float depthCoef, float discon_thresh, float noise_thresh, float area_max) {
+
+	const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
+	const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+	if (x < size.width && y < size.height) {
+		Mask mask(0);
+
+		const float d = depth.tex2D((int)x, (int)y);
+		// Multiples of pixel size at given depth
+		//const float threshold = (depthCoef / ((depthCoef / d) - (radius+disconDisparities-1))) - d;
+		const float threshold = depthCoef * d;  // Where depthCoef = 1 / focal * N, N = number of pixel distances equal to a discon.
+
+		if (d > minDepth && d < maxDepth) {
+			/* Orts-Escolano S. et al. 2016. Holoportation: Virtual 3D teleportation in real-time.
+			 * This paper just says to remove values around discontinuities. */
+
+			// Find max change in depth gradient in each direction
+			const float g1 = fabsf((depth.tex2D(x-1, y) - d) - (d - depth.tex2D(x+1,y)));
+			const float g2 = fabsf((depth.tex2D(x, y-1) - d) - (d - depth.tex2D(x,y+1)));
+			const float g3 = fabsf((depth.tex2D(x-1, y-1) - d) - (d - depth.tex2D(x+1,y+1)));
+			const float g4 = fabsf((depth.tex2D(x+1, y-1) - d) - (d - depth.tex2D(x-1,y+1)));
+			const float g = max(g1,max(g2,(max(g3,g4))));
+
+			// Calculate support window area
+			const uchar4 sup = support.tex2D((int)x, (int)y);
+			const float supx = min(sup.x,sup.y);
+			const float supy = min(sup.z,sup.w);
+			const float area = supx * supy;
+
+			float grad_weight = min(1.0f, g / threshold);
+			float area_weight = min(1.0f, area / area_max);
+
+			if (grad_weight * (1.0f - area_weight) > discon_thresh) mask.isDiscontinuity(true);
+			if (grad_weight * (area_weight) > noise_thresh) mask.isNoise(true);
+		}
+
+		mask_out(x,y) = (int)mask;
+	}
+}
+
+void ftl::cuda::discontinuity(	ftl::cuda::TextureObject<uint8_t> &mask_out, ftl::cuda::TextureObject<uchar4> &support,
 								ftl::cuda::TextureObject<float> &depth,
 								const cv::Size size, const double minDepth, const double maxDepth,
-								int discon, float thresh, cudaStream_t stream) {
+								int discon, float depthCoef, cudaStream_t stream) {
 	
 	const dim3 gridSize((size.width + T_PER_BLOCK - 1)/T_PER_BLOCK, (size.height + T_PER_BLOCK - 1)/T_PER_BLOCK);
 	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
 
-	discontinuity_kernel<<<gridSize, blockSize, 0, stream>>>(mask_out, support, depth, size, minDepth, maxDepth, thresh, discon);
+	discontinuity_kernel<<<gridSize, blockSize, 0, stream>>>(mask_out, support, depth, size, minDepth, maxDepth, depthCoef, discon);
 	cudaSafeCall( cudaGetLastError() );
 
 #ifdef _DEBUG
@@ -64,21 +116,57 @@ void ftl::cuda::discontinuity(	ftl::cuda::TextureObject<int> &mask_out, ftl::cud
 #endif
 }
 
-__global__ void cull_discontinuity_kernel(ftl::cuda::TextureObject<int> mask, ftl::cuda::TextureObject<float> depth) {
+void ftl::cuda::discontinuity(	ftl::cuda::TextureObject<uint8_t> &mask_out, ftl::cuda::TextureObject<uchar4> &support,
+		ftl::cuda::TextureObject<float> &depth,
+		const cv::Size size, const double minDepth, const double maxDepth,
+		float depthCoef, float discon_thresh, float noise_thresh, float area_max, cudaStream_t stream) {
+
+	const dim3 gridSize((size.width + T_PER_BLOCK - 1)/T_PER_BLOCK, (size.height + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	discontinuity_kernel<<<gridSize, blockSize, 0, stream>>>(mask_out, support, depth, size, minDepth, maxDepth, depthCoef, discon_thresh, noise_thresh, area_max);
+	cudaSafeCall( cudaGetLastError() );
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	#endif
+}
+
+// =============================================================================
+
+template <int RADIUS>
+__global__ void cull_mask_kernel(ftl::cuda::TextureObject<uint8_t> mask, ftl::cuda::TextureObject<float> depth, uint8_t id) {
 	const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
 	const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
 
-	if (x < depth.width() && y < depth.height()) {
-		Mask m(mask.tex2D((int)x,(int)y));
-		if (m.isDiscontinuity()) depth(x,y) = 0.0f;
+	if (x < depth.width()-RADIUS && y < depth.height()-RADIUS) {
+		bool isdiscon = false;
+
+		#pragma unroll
+		for (int v=-RADIUS; v<=RADIUS; ++v) {
+		#pragma unroll
+		for (int u=-RADIUS; u<=RADIUS; ++u) {
+			Mask m(mask.tex2D((int)x+u,(int)y+v));
+			isdiscon = isdiscon || m.is(id);
+		}
+		}
+
+		if (isdiscon) {
+			depth(x,y) = 0.0f;
+			Mask m(mask.tex2D((int)x,(int)y));
+			m.isDiscontinuity(true);
+			mask(x,y) = m;
+		}
 	}
 }
 
-void ftl::cuda::cull_discontinuity(ftl::cuda::TextureObject<int> &mask, ftl::cuda::TextureObject<float> &depth, cudaStream_t stream) {
+void ftl::cuda::cull_mask(ftl::cuda::TextureObject<uint8_t> &mask, ftl::cuda::TextureObject<float> &depth, uint8_t id, unsigned int radius, cudaStream_t stream) {
 	const dim3 gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
 	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
 
-	cull_discontinuity_kernel<<<gridSize, blockSize, 0, stream>>>(mask, depth);
+	for (unsigned int i=0; i<radius; ++i) {
+		cull_mask_kernel<1><<<gridSize, blockSize, 0, stream>>>(mask, depth, id);
+	}
 	cudaSafeCall( cudaGetLastError() );
 
 #ifdef _DEBUG
diff --git a/components/operators/src/mls.cu b/components/operators/src/mls.cu
index e07178cdf9606444c307f59a2adbb8818b049ed4..5d25fc6c0e8648318a242ff08fcec26648086f07 100644
--- a/components/operators/src/mls.cu
+++ b/components/operators/src/mls.cu
@@ -423,7 +423,7 @@ void ftl::cuda::colour_mls_smooth_csr(
 		w *= ftl::cuda::colourWeighting(c0,c,colour_smoothing);
 
 		// Gauss approx weighting function using point distance
-		w = ftl::cuda::spatialWeighting(X,Xi,smoothing*w);
+		w = ftl::cuda::spatialWeighting(X,Xi,d0*smoothing*w);
 
 		aX += Xi*w;
 		nX += Ni*w;
@@ -501,7 +501,7 @@ template <int RADIUS>
 		w *= ftl::cuda::colourWeighting(c0,c,colour_smoothing);
 
 		// Gauss approx weighting function using point distance
-		w = ftl::cuda::spatialWeighting(X,Xi,smoothing*w);
+		w = ftl::cuda::spatialWeighting(X,Xi,d0*smoothing*w);
 
 		aX += Ai*w;
 		nX += Ni*w;
diff --git a/components/operators/src/mvmls.cpp b/components/operators/src/mvmls.cpp
index de69a0691441c7661dc3ae23d51639440a83654f..ab150ed459862a453f5dce98660885a65b3e0f0f 100644
--- a/components/operators/src/mvmls.cpp
+++ b/components/operators/src/mvmls.cpp
@@ -19,7 +19,9 @@ MultiViewMLS::~MultiViewMLS() {
 bool MultiViewMLS::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream) {
     cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 
-    float thresh = config()->value("mls_threshold", 0.4f);
+   // float thresh = config()->value("mls_threshold", 0.4f);
+	float disconPixels = config()->value("discon_pixels", 100.0f);  // Max before definitely not same surface
+	
 	float col_smooth = config()->value("mls_colour_smoothing", 30.0f);
 	int iters = config()->value("mls_iterations", 3);
 	int radius = config()->value("mls_radius",5);
@@ -37,7 +39,7 @@ bool MultiViewMLS::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cuda
     params.fill_threshold = config()->value("fill_threshold", 0.0f);
 	params.match_threshold = config()->value("match_threshold", 0.3f);
     params.colour_smooth = config()->value("colour_smooth", 150.0f);
-    params.spatial_smooth = config()->value("spatial_smooth", 0.04f);
+    //params.spatial_smooth = config()->value("spatial_smooth", 0.04f);
     params.cost_ratio = config()->value("cost_ratio", 0.2f);
 	params.cost_threshold = config()->value("cost_threshold", 1.0f);
 
@@ -120,7 +122,7 @@ bool MultiViewMLS::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cuda
                         // TODO: Add normals and other things...
                         f1.getTexture<short2>(Channel::Screen),
                         f1.getTexture<float>(Channel::Confidence),
-                        f1.getTexture<int>(Channel::Mask),
+                        f1.getTexture<uint8_t>(Channel::Mask),
                         pose2,
                         f1.getLeftCamera(),
                         f2.getLeftCamera(),
@@ -215,6 +217,8 @@ bool MultiViewMLS::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cuda
 				);
 			}
 
+			float thresh = (1.0f / f.getLeft().fx) * disconPixels;
+
             ftl::cuda::mls_aggr_horiz(
                 f.createTexture<uchar4>(Channel::Support2),
                 f.createTexture<float4>(Channel::Normals),
diff --git a/components/operators/src/mvmls_cuda.hpp b/components/operators/src/mvmls_cuda.hpp
index 5faeb47533a16e7c3e13bfc5e23e826aa8b836e3..1189ca758a4c2765b1a78b2a9f728303ee2b1384 100644
--- a/components/operators/src/mvmls_cuda.hpp
+++ b/components/operators/src/mvmls_cuda.hpp
@@ -27,7 +27,7 @@ void correspondence(
         ftl::cuda::TextureObject<uchar4> &c2,
         ftl::cuda::TextureObject<short2> &screen,
 		ftl::cuda::TextureObject<float> &conf,
-		ftl::cuda::TextureObject<int> &mask,
+		ftl::cuda::TextureObject<uint8_t> &mask,
         float4x4 &pose,
         const ftl::rgbd::Camera &cam1,
         const ftl::rgbd::Camera &cam2, const ftl::cuda::MvMLSParams &params, int func,
diff --git a/components/operators/src/normals.cpp b/components/operators/src/normals.cpp
index 0551a1e4ecb686d6b47305e9c081718680e374a7..3a4e7f5dbe5b1b02ca16ba5e7aa9d21c0b63dd5c 100644
--- a/components/operators/src/normals.cpp
+++ b/components/operators/src/normals.cpp
@@ -3,6 +3,7 @@
 #include <ftl/utility/matrix_conversion.hpp>
 
 using ftl::operators::Normals;
+using ftl::operators::NormalDot;
 using ftl::operators::SmoothNormals;
 using ftl::codecs::Channel;
 using ftl::rgbd::Format;
@@ -34,6 +35,37 @@ bool Normals::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t st
 	return true;
 }
 
+// =============================================================================
+
+NormalDot::NormalDot(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+NormalDot::~NormalDot() {
+
+}
+
+bool NormalDot::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t stream) {
+	if (!in.hasChannel(Channel::Depth)) {
+		throw FTL_Error("Missing depth channel in Normals operator");
+	}
+
+	if (out.hasChannel(Channel::Normals)) {
+		//LOG(WARNING) << "Output already has normals";
+		return true;
+	}
+
+	ftl::cuda::normals_dot(
+		out.createTexture<float>(Channel::Normals, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+		in.createTexture<float>(Channel::Depth),
+		in.getLeftCamera(), stream
+	);
+
+	return true;
+}
+
+// =============================================================================
+
 
 SmoothNormals::SmoothNormals(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
 
diff --git a/components/operators/src/segmentation.cpp b/components/operators/src/segmentation.cpp
index 32de62112d856cb186c6db21bf3534d0733246ce..d2201a088fa636bc0fb2a15215443a95ce3c4b5d 100644
--- a/components/operators/src/segmentation.cpp
+++ b/components/operators/src/segmentation.cpp
@@ -20,7 +20,7 @@ bool CrossSupport::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream
 	if (use_mask && !in.hasChannel(Channel::Support2)) {
 		if (!in.hasChannel(Channel::Mask)) return false;
 		ftl::cuda::support_region(
-			in.createTexture<int>(Channel::Mask),
+			in.createTexture<uint8_t>(Channel::Mask),
 			out.createTexture<uchar4>(Channel::Support2, ftl::rgbd::Format<uchar4>(in.get<cv::cuda::GpuMat>(Channel::Colour).size())),
 			config()->value("v_max", 5),
 			config()->value("h_max", 5),
@@ -30,7 +30,7 @@ bool CrossSupport::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream
 		ftl::cuda::support_region(
 			in.createTexture<uchar4>(Channel::Colour),
 			out.createTexture<uchar4>(Channel::Support1, ftl::rgbd::Format<uchar4>(in.get<cv::cuda::GpuMat>(Channel::Colour).size())),
-			config()->value("tau", 5.0f),
+			config()->value("tau", 10.0f),
 			config()->value("v_max", 5),
 			config()->value("h_max", 5),
 			config()->value("symmetric", true), stream
diff --git a/components/operators/src/segmentation.cu b/components/operators/src/segmentation.cu
index aaa81e2ad98b5171572b6768754b93f32abcd1eb..f38008e7b5bb9802dd49d98d86f4ddacf44dd1f9 100644
--- a/components/operators/src/segmentation.cu
+++ b/components/operators/src/segmentation.cu
@@ -1,5 +1,5 @@
 #include "segmentation_cuda.hpp"
-#include "mask_cuda.hpp"
+#include <ftl/operators/mask_cuda.hpp>
 
 #define T_PER_BLOCK 8
 
@@ -91,7 +91,7 @@ __device__ uchar4 calculate_support_region(const TextureObject<T> &img, int x, i
     return result;
 }
 
-__device__ uchar4 calculate_support_region(const TextureObject<int> &img, int x, int y, int v_max, int h_max) {
+__device__ uchar4 calculate_support_region(const TextureObject<uint8_t> &img, int x, int y, int v_max, int h_max) {
     int x_min = max(0, x - h_max);
     int x_max = min(img.width()-1, x + h_max);
     int y_min = max(0, y - v_max);
@@ -159,7 +159,7 @@ __global__ void support_region_kernel(TextureObject<T> img, TextureObject<uchar4
     region(x,y) = calculate_support_region<T,SYM>(img, x, y, tau, v_max, h_max);
 }
 
-__global__ void support_region_kernel(TextureObject<int> img, TextureObject<uchar4> region, int v_max, int h_max) {
+__global__ void support_region_kernel(TextureObject<uint8_t> img, TextureObject<uchar4> region, int v_max, int h_max) {
     const int x = blockIdx.x*blockDim.x + threadIdx.x;
     const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
@@ -212,7 +212,7 @@ void ftl::cuda::support_region(
 }
 
 void ftl::cuda::support_region(
-		ftl::cuda::TextureObject<int> &mask,
+		ftl::cuda::TextureObject<uint8_t> &mask,
 		ftl::cuda::TextureObject<uchar4> &region,
 		int v_max,
 		int h_max,
diff --git a/components/operators/src/segmentation_cuda.hpp b/components/operators/src/segmentation_cuda.hpp
index 1383489337dc968a33ec630facb597920518e2bf..445ed7e6d0f2624808232e66d834a360c6d798e8 100644
--- a/components/operators/src/segmentation_cuda.hpp
+++ b/components/operators/src/segmentation_cuda.hpp
@@ -19,7 +19,7 @@ void support_region(
 		cudaStream_t stream);
 
 void support_region(
-		ftl::cuda::TextureObject<int> &mask,
+		ftl::cuda::TextureObject<uint8_t> &mask,
 		ftl::cuda::TextureObject<uchar4> &region,
 		int v_max, int h_max, bool sym,
 		cudaStream_t stream);
diff --git a/components/operators/src/smoothing.cpp b/components/operators/src/smoothing.cpp
index 94eda17700e80a760b2aa8a11e021b4bcd59d073..7f9cb50d3d682d90f899e2069a77ed1efb62af2c 100644
--- a/components/operators/src/smoothing.cpp
+++ b/components/operators/src/smoothing.cpp
@@ -31,6 +31,8 @@ bool HFSmoother::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStream_t
     //int levels = max(0, min(config()->value("levels",0), 4));
     int iters = config()->value("iterations",5);
 
+	if (!in.hasChannel(Channel::Depth)) return false;
+
 	// FIXME: in and out are assumed to be the same
 
     for (int i=0; i<iters; ++i) {
diff --git a/components/renderers/cpp/include/ftl/cuda/mask.hpp b/components/renderers/cpp/include/ftl/cuda/mask.hpp
deleted file mode 100644
index 3f49f3bfc65e67186cc8caf321743ae2800805e7..0000000000000000000000000000000000000000
--- a/components/renderers/cpp/include/ftl/cuda/mask.hpp
+++ /dev/null
@@ -1,43 +0,0 @@
-#ifndef _FTL_CUDA_MASK_HPP_
-#define _FTL_CUDA_MASK_HPP_
-
-namespace ftl {
-namespace cuda {
-
-/**
- * Wrap an int mask value used to flag individual depth pixels.
- */
-class Mask {
-	public:
-	__device__ inline Mask() : v_(0) {}
-	__device__ explicit inline Mask(int v) : v_(v) {}
-	#ifdef __CUDACC__
-	__device__ inline Mask(const ftl::cuda::TextureObject<int> &m, int x, int y) : v_(m.tex2D(x,y)) {}
-	#endif
-	__device__ inline operator int() const { return v_; }
-
-    __device__ inline bool is(int m) const { return v_ & m; }
-
-	__device__ inline bool isFilled() const { return v_ & kMask_Filled; }
-	__device__ inline bool isDiscontinuity() const { return v_ & kMask_Discontinuity; }
-	__device__ inline bool hasCorrespondence() const { return v_ & kMask_Correspondence; }
-	__device__ inline bool isBad() const { return v_ & kMask_Bad; }
-
-	__device__ inline void isFilled(bool v) { v_ = (v) ? v_ | kMask_Filled : v_ & (~kMask_Filled); }
-	__device__ inline void isDiscontinuity(bool v) { v_ = (v) ? v_ | kMask_Discontinuity : v_ & (~kMask_Discontinuity); }
-	__device__ inline void hasCorrespondence(bool v) { v_ = (v) ? v_ | kMask_Correspondence : v_ & (~kMask_Correspondence); }
-	__device__ inline void isBad(bool v) { v_ = (v) ? v_ | kMask_Bad : v_ & (~kMask_Bad); }
-
-    static constexpr int kMask_Filled = 0x0001;
-	static constexpr int kMask_Discontinuity = 0x0002;
-	static constexpr int kMask_Correspondence = 0x0004;
-	static constexpr int kMask_Bad = 0x0008;
-
-	private:
-	int v_;
-};
-
-}
-}
-
-#endif
diff --git a/components/renderers/cpp/include/ftl/cuda/normals.hpp b/components/renderers/cpp/include/ftl/cuda/normals.hpp
index bbf690f4f66178297158dea35528ba01629445a1..da07582d3155485f32c13d34b38c65d88ed4da73 100644
--- a/components/renderers/cpp/include/ftl/cuda/normals.hpp
+++ b/components/renderers/cpp/include/ftl/cuda/normals.hpp
@@ -37,6 +37,11 @@ void normals(ftl::cuda::TextureObject<float4> &output,
         const ftl::rgbd::Camera &camera,
         cudaStream_t stream);
 
+void normals_dot(ftl::cuda::TextureObject<float> &output,
+        ftl::cuda::TextureObject<float> &input,
+        const ftl::rgbd::Camera &camera,
+        cudaStream_t stream);
+
 void normal_visualise(ftl::cuda::TextureObject<float4> &norm,
         ftl::cuda::TextureObject<uchar4> &output,
         const float3 &light, const uchar4 &diffuse, const uchar4 &ambient,
diff --git a/components/renderers/cpp/include/ftl/render/CUDARender.hpp b/components/renderers/cpp/include/ftl/render/CUDARender.hpp
index 3414f43ca244f50d2d2f3306f1ca4206dee382c3..3d911b6accdb53001f9889a66478face2d65af77 100644
--- a/components/renderers/cpp/include/ftl/render/CUDARender.hpp
+++ b/components/renderers/cpp/include/ftl/render/CUDARender.hpp
@@ -89,6 +89,7 @@ class CUDARender : public ftl::render::Renderer {
 	void _renderPass2(ftl::codecs::Channels<0>, const Eigen::Matrix4d &t);
 
 	bool _alreadySeen() const { return last_frame_ == scene_->timestamp; }
+	void _adjustDepthThresholds(const ftl::rgbd::Camera &fcam);
 };
 
 }
diff --git a/components/renderers/cpp/include/ftl/render/render_params.hpp b/components/renderers/cpp/include/ftl/render/render_params.hpp
index 8a4da170e0d35f7a1cf1f2587fbdb77b0bd53e63..8f9ae61f53ddadbb4e29cb451a31e863aaa1a60a 100644
--- a/components/renderers/cpp/include/ftl/render/render_params.hpp
+++ b/components/renderers/cpp/include/ftl/render/render_params.hpp
@@ -50,7 +50,8 @@ enum class ViewPortMode : uint8_t {
 
 struct Parameters {
 	uint m_flags;
-	float depthThreshold;
+	float disconDisparities;
+	float depthCoef;
 	int triangle_limit;
 
 	ftl::rgbd::Camera camera;  // Virtual camera intrinsics
diff --git a/components/renderers/cpp/src/CUDARender.cpp b/components/renderers/cpp/src/CUDARender.cpp
index 8bc1fbd87adac1d9e7a00d8eeaa662caffedfab3..d407db476a0c4fc04b015043ee5de794e5809206 100644
--- a/components/renderers/cpp/src/CUDARender.cpp
+++ b/components/renderers/cpp/src/CUDARender.cpp
@@ -3,7 +3,7 @@
 #include "splatter_cuda.hpp"
 #include <ftl/cuda/points.hpp>
 #include <ftl/cuda/normals.hpp>
-#include <ftl/cuda/mask.hpp>
+#include <ftl/operators/mask_cuda.hpp>
 
 #define LOGURU_REPLACE_GLOG 1
 #include <loguru.hpp>
@@ -187,6 +187,8 @@ void CUDARender::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann
 			return;
 		}
 
+		_adjustDepthThresholds(f.getLeftCamera());
+
 		auto transform = MatrixConversion::toCUDA(f.getPose().cast<float>().inverse() * t.cast<float>().inverse()) * poseInverse_;
 		auto transformR = MatrixConversion::toCUDA(f.getPose().cast<float>().inverse()).getFloat3x3();
 
@@ -291,6 +293,10 @@ void CUDARender::_dibr(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 	temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(Channel::Depth), CV_32F, 1.0f / 100000.0f, cvstream);
 }
 
+void CUDARender::_adjustDepthThresholds(const ftl::rgbd::Camera &fcam) {
+	params_.depthCoef = fcam.baseline*fcam.fx;
+}
+
 void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStream_t stream) {
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 
@@ -316,6 +322,8 @@ void CUDARender::_mesh(ftl::rgbd::Frame &out, const Eigen::Matrix4d &t, cudaStre
 		//auto pose = MatrixConversion::toCUDA(t.cast<float>() * f.getPose().cast<float>());
 		auto transform = pose_ * MatrixConversion::toCUDA(t.cast<float>() * f.getPose().cast<float>());
 
+		_adjustDepthThresholds(f.getLeftCamera());
+
 		// Calculate and save virtual view screen position of each source pixel
 		if (f.hasChannel(Channel::Depth)) {
 			ftl::cuda::screen_coord(
@@ -475,7 +483,9 @@ void CUDARender::_updateParameters(ftl::rgbd::Frame &out) {
 
 	// Parameters object to pass to CUDA describing the camera
 	params_.triangle_limit = value("triangle_limit", 200);
-	params_.depthThreshold = value("depth_threshold", 0.04f);
+	//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_.m_flags = 0;
 	if (value("normal_weight_colours", true)) params_.m_flags |= ftl::render::kNormalWeightColours;
 	params_.camera = camera;
@@ -486,6 +496,7 @@ void CUDARender::_updateParameters(ftl::rgbd::Frame &out) {
 
 void CUDARender::_preprocessColours() {
 	bool show_discon = value("show_discontinuity_mask", false);
+	bool show_noise = value("show_noise_mask", false);
 	bool show_fill = value("show_filled", false);
 	bool colour_sources = value("colour_sources", false);
 
@@ -501,11 +512,14 @@ void CUDARender::_preprocessColours() {
 		}
 
 		if (f.hasChannel(Channel::Mask)) {
+			if (show_noise) {
+				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<uint8_t>(Channel::Mask), Mask::kMask_Noise, make_uchar4(0,255,0,255), stream_);
+			}
 			if (show_discon) {
-				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<int>(Channel::Mask), Mask::kMask_Discontinuity, make_uchar4(0,0,255,255), stream_);
+				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<uint8_t>(Channel::Mask), Mask::kMask_Discontinuity, make_uchar4(0,0,255,255), stream_);
 			}
 			if (show_fill) {
-				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<int>(Channel::Mask), Mask::kMask_Filled, make_uchar4(0,255,0,255), stream_);
+				ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<uint8_t>(Channel::Mask), Mask::kMask_Filled, make_uchar4(0,255,0,255), stream_);
 			}
 		}
 
@@ -637,6 +651,7 @@ void CUDARender::_renderPass2(Channels<0> chans, const Eigen::Matrix4d &t) {
 		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;
diff --git a/components/renderers/cpp/src/points.cu b/components/renderers/cpp/src/OLD_points.cu
similarity index 100%
rename from components/renderers/cpp/src/points.cu
rename to components/renderers/cpp/src/OLD_points.cu
diff --git a/components/renderers/cpp/src/splatter.cu b/components/renderers/cpp/src/OLD_splatter.cu
similarity index 100%
rename from components/renderers/cpp/src/splatter.cu
rename to components/renderers/cpp/src/OLD_splatter.cu
diff --git a/components/renderers/cpp/src/mask.cu b/components/renderers/cpp/src/mask.cu
index 1adb4fb75c4c25d4ee70e8d1f378a43702142745..e46c2a131e94ef7fa43d8d1805ff96d8091026ef 100644
--- a/components/renderers/cpp/src/mask.cu
+++ b/components/renderers/cpp/src/mask.cu
@@ -1,5 +1,5 @@
 #include "splatter_cuda.hpp"
-#include <ftl/cuda/mask.hpp>
+#include <ftl/operators/mask_cuda.hpp>
 
 using ftl::cuda::TextureObject;
 using ftl::cuda::Mask;
@@ -8,7 +8,7 @@ using ftl::cuda::Mask;
 
 __global__ void show_mask_kernel(
         TextureObject<uchar4> colour,
-        TextureObject<int> mask,
+        TextureObject<uint8_t> mask,
         int id, uchar4 style) {
         
 	const int x = (blockIdx.x*blockDim.x + threadIdx.x);
@@ -26,7 +26,7 @@ __global__ void show_mask_kernel(
 
 void ftl::cuda::show_mask(
         TextureObject<uchar4> &colour,
-        TextureObject<int> &mask,
+        TextureObject<uint8_t> &mask,
         int id, uchar4 style, cudaStream_t stream) {
 	const dim3 gridSize((colour.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (colour.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
 	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
diff --git a/components/renderers/cpp/src/normals.cu b/components/renderers/cpp/src/normals.cu
index 31034c0af6059f2b8014d7af780bd082bb34868a..eb2a8fc892562ac275b0d6dd1ab0229b02c34b12 100644
--- a/components/renderers/cpp/src/normals.cu
+++ b/components/renderers/cpp/src/normals.cu
@@ -355,6 +355,58 @@ void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
     #endif
 }
 
+// =============================================================================
+
+__global__ void computeNormals_dot_kernel(ftl::cuda::TextureObject<float> output,
+		ftl::cuda::TextureObject<float> input, ftl::rgbd::Camera camera) {
+	const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
+	const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+	if(x >= input.width() || y >= input.height()) return;
+
+	float out = 0.0f;
+
+	if(x > 0 && x < input.width()-1 && y > 0 && y < input.height()-1) {
+		float d = input.tex2D((int)x+0, (int)y+0);
+		const float3 CC = camera.screenToCam(x+0, y+0, d);
+		const float3 PC = camera.screenToCam(x+0, y+1, input.tex2D((int)x+0, (int)y+1));
+		const float3 CP = camera.screenToCam(x+1, y+0, input.tex2D((int)x+1, (int)y+0));
+		const float3 MC = camera.screenToCam(x+0, y-1, input.tex2D((int)x+0, (int)y-1));
+		const float3 CM = camera.screenToCam(x-1, y+0, input.tex2D((int)x-1, (int)y+0));
+
+		//if(CC.z <  && PC.x != MINF && CP.x != MINF && MC.x != MINF && CM.x != MINF) {
+		if (isValid(camera,CC) && isValid(camera,PC) && isValid(camera,CP) && isValid(camera,MC) && isValid(camera,CM)) {
+			float3 n = cross(PC-MC, CP-CM);
+			const float  l = length(n);
+
+			if(l > 0.0f) {
+				n = n / -l;
+				float3 ray = camera.screenToCam(x, y, d);
+				ray = ray / length(ray);
+				out = dot(ray,n);
+			}
+		}
+	}
+
+	output(x,y) = out;
+}
+
+void ftl::cuda::normals_dot(ftl::cuda::TextureObject<float> &output,
+		ftl::cuda::TextureObject<float> &input,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream) {
+	const dim3 gridSize((input.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (input.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	computeNormals_dot_kernel<<<gridSize, blockSize, 0, stream>>>(output, input, camera);
+	cudaSafeCall( cudaGetLastError() );
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	//cutilCheckMsg(__FUNCTION__);
+	#endif
+}
+
 //==============================================================================
 
 __global__ void vis_normals_kernel(ftl::cuda::TextureObject<float4> norm,
diff --git a/components/renderers/cpp/src/reprojection.cu b/components/renderers/cpp/src/reprojection.cu
index 808501a4ad66406e284aa7030a939e1e24038c85..703fd4becc7ebca7841dc07c956783579ca3a8f9 100644
--- a/components/renderers/cpp/src/reprojection.cu
+++ b/components/renderers/cpp/src/reprojection.cu
@@ -65,6 +65,30 @@ __device__ inline uint2 convertScreen<ViewPortMode::Warping>(const Parameters &p
 	return params.viewport.reverseMap(params.camera, make_float2(x,y));
 }
 
+template <typename A>
+__device__ inline auto getInput(TextureObject<A> &in, const float2 &screen, float width, float height) {
+	const float inSX = float(in.width()) / width;
+	const float inSY = float(in.height()) / height;
+	return in.tex2D(screen.x*inSX, screen.y*inSY); 
+}
+
+__device__ float weightByNormal(TextureObject<float4> &normals, int x, int y, const float3x3 &transformR, const float2 &screenPos, const ftl::rgbd::Camera &camera) {
+	// Calculate the dot product of surface normal and camera ray
+	const float3 n = transformR * make_float3(normals.tex2D(x, y));
+	float3 ray = camera.screenToCam(screenPos.x, screenPos.y, 1.0f);
+	ray = ray / length(ray);
+
+	// Allow slightly beyond 90 degrees due to normal estimation errors
+	const float dotproduct = (max(dot(ray,n),-0.1f)+0.1) / 1.1f;
+	return dotproduct;
+}
+
+__device__ float depthMatching(const Parameters &params, float d1, float d2) {
+	// TODO: Consider a slightly different pixel size check
+	const float threshold = (params.depthCoef / ((params.depthCoef / d2) - 1.0f)) - d2;
+	return (fabs(d1 - d2) <= threshold) ? 1.0f : 0.0f;
+}
+
 /*
  * Full reprojection with normals and depth
  */
@@ -83,53 +107,42 @@ __global__ void reprojection_kernel(
 	const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
 	const float d = depth_in.tex2D((int)x, (int)y);
-	if (d < params.camera.minDepth || d > params.camera.maxDepth) return;
-
-	//const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d);
-	//if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
-
-	//const uint2 rpt = make_uint2(x,y);
-	const uint2 rpt = convertScreen<VPMODE>(params, x, y);
-	const float3 camPos = transform * params.camera.screenToCam(rpt.x, rpt.y, d);
-	if (camPos.z < camera.minDepth) return;
-	if (camPos.z > camera.maxDepth) return;
-	const float2 screenPos = camera.camToScreen<float2>(camPos);
-
-	// Not on screen so stop now...
-	if (screenPos.x >= depth_src.width() || screenPos.y >= depth_src.height()) return;
-            
-	// Calculate the dot product of surface normal and camera ray
-	const float3 n = transformR * make_float3(normals.tex2D((int)x, (int)y));
-	float3 ray = camera.screenToCam(screenPos.x, screenPos.y, 1.0f);
-	ray = ray / length(ray);
-
-	// Allow slightly beyond 90 degrees due to normal estimation errors
-	const float dotproduct = (max(dot(ray,n),-0.1f)+0.1) / 1.1f;
-    
-	const float d2 = depth_src.tex2D(int(screenPos.x+0.5f), int(screenPos.y+0.5f));
-
-	const float inSX = float(in.width()) / float(depth_src.width());
-	const float inSY = float(in.height()) / float(depth_src.height());
-	const auto input = in.tex2D(screenPos.x*inSX, screenPos.y*inSY); //generateInput(in.tex2D((int)screenPos.x, (int)screenPos.y), params, worldPos);
-
-	// TODO: Z checks need to interpolate between neighbors if large triangles are used
-	//float weight = ftl::cuda::weighting(fabs(camPos.z - d2), params.depthThreshold);
-	// TODO: Depth threshold should relate to pixel size
-	float weight = (fabs(camPos.z - d2) <= params.depthThreshold) ? 1.0f : 0.0f;
-
-	/* Buehler C. et al. 2001. Unstructured Lumigraph Rendering. */
-	/* Orts-Escolano S. et al. 2016. Holoportation: Virtual 3D teleportation in real-time. */
-	// This is the simple naive colour weighting. It might be good
-	// enough for our purposes if the alignment step prevents ghosting
-	// TODO: Use depth and perhaps the neighbourhood consistency in:
-	//     Kuster C. et al. 2011. FreeCam: A hybrid camera system for interactive free-viewpoint video
-	if (params.m_flags & ftl::render::kNormalWeightColours) weight *= dotproduct;
-
-	const B weighted = make<B>(input) * weight; //weightInput(input, weight);
-
-	if (weight > 0.0f) {
-		accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
-		//out(screenPos.x, screenPos.y) = input;
+	if (d > params.camera.minDepth && d < params.camera.maxDepth) {
+		const uint2 rpt = convertScreen<VPMODE>(params, x, y);
+		const float3 camPos = transform * params.camera.screenToCam(rpt.x, rpt.y, d);
+		if (camPos.z > camera.minDepth && camPos.z < camera.maxDepth) {
+			const float2 screenPos = camera.camToScreen<float2>(camPos);
+
+			// Not on screen so stop now...
+			if (screenPos.x < depth_src.width() && screenPos.y < depth_src.height()) {
+				const float d2 = depth_src.tex2D(int(screenPos.x+0.5f), int(screenPos.y+0.5f));
+
+				const auto input = getInput(in, screenPos, depth_src.width(), depth_src.height()); 
+
+				// Boolean match (0 or 1 weight). 1.0 if depths are sufficiently close
+				float weight = depthMatching(params, camPos.z, d2);
+
+				// TODO: Weight by distance to discontinuity? Perhaps as an alternative to
+				// removing a discontinuity. This would also gradually blend colours from
+				// multiple cameras that otherwise might jump when one cameras input is lost
+				// at an invalid patch.
+
+				/* Buehler C. et al. 2001. Unstructured Lumigraph Rendering. */
+				/* Orts-Escolano S. et al. 2016. Holoportation: Virtual 3D teleportation in real-time. */
+				// This is the simple naive colour weighting. It might be good
+				// enough for our purposes if the alignment step prevents ghosting
+				// TODO: Use depth and perhaps the neighbourhood consistency in:
+				//     Kuster C. et al. 2011. FreeCam: A hybrid camera system for interactive free-viewpoint video
+				if (params.m_flags & ftl::render::kNormalWeightColours)
+					weight *= weightByNormal(normals, x, y, transformR, screenPos, camera);
+
+				const B weighted = make<B>(input) * weight; //weightInput(input, weight);
+
+				if (weight > 0.0f) {
+					accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
+				}
+			}
+		}
 	}
 }
 
@@ -196,9 +209,7 @@ template void ftl::cuda::reproject(
 //  Without normals
 //==============================================================================
 
-/*
- * Pass 2: Accumulate attribute contributions if the points pass a visibility test.
- */
+
  template <typename A, typename B>
 __global__ void reprojection_kernel(
         TextureObject<A> in,				// Attribute input
@@ -213,31 +224,22 @@ __global__ void reprojection_kernel(
 	const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
 	const float d = depth_in.tex2D((int)x, (int)y);
-	if (d < params.camera.minDepth || d > params.camera.maxDepth) return;
-
-	//const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d);
-	//if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
-
-	const float3 camPos = poseInv * params.camera.screenToCam(x, y, d);
-	if (camPos.z < camera.minDepth) return;
-	if (camPos.z > camera.maxDepth) return;
-	const float2 screenPos = camera.camToScreen<float2>(camPos);
-
-	// Not on screen so stop now...
-	if (screenPos.x >= depth_src.width() || screenPos.y >= depth_src.height()) return;
-    
-	const float d2 = depth_src.tex2D((int)(screenPos.x+0.5f), (int)(screenPos.y+0.5f));
-
-	const float inSX = float(in.width()) / float(depth_src.width());
-	const float inSY = float(in.height()) / float(depth_src.height());
-	const auto input = in.tex2D(screenPos.x*inSX, screenPos.y*inSY); //generateInput(in.tex2D((int)screenPos.x, (int)screenPos.y), params, worldPos);
-
-	float weight = ftl::cuda::weighting(fabs(camPos.z - d2), 0.02f);
-	const B weighted = make<B>(input) * weight;
-
-	if (weight > 0.0f) {
-		accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
-		//out(screenPos.x, screenPos.y) = input;
+	if (d > params.camera.minDepth && d < params.camera.maxDepth) {
+		const float3 camPos = poseInv * params.camera.screenToCam(x, y, d);
+		if (camPos.z > camera.minDepth && camPos.z > camera.maxDepth) {
+			const float2 screenPos = camera.camToScreen<float2>(camPos);
+
+			if (screenPos.x < depth_src.width() && screenPos.y < depth_src.height()) {
+				const float d2 = depth_src.tex2D((int)(screenPos.x+0.5f), (int)(screenPos.y+0.5f));
+				const auto input = getInput(in, screenPos, depth_src.width(), depth_src.height());
+				float weight = depthMatching(params, camPos.z, d2);
+				const B weighted = make<B>(input) * weight;
+
+				if (weight > 0.0f) {
+					accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
+				}
+			}
+		}
 	}
 }
 
@@ -317,29 +319,19 @@ __global__ void reprojection_kernel(
 	const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
 	const float d = depth_in.tex2D((int)x, (int)y);
-	if (d < params.camera.minDepth || d > params.camera.maxDepth) return;
-
-	//const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d);
-	//if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
+	if (d > params.camera.minDepth && d < params.camera.maxDepth) {
+		const float3 camPos = poseInv * params.camera.screenToCam(x, y, d);
+		const float2 screenPos = camera.camToScreen<float2>(camPos);
 
-	const float3 camPos = poseInv * params.camera.screenToCam(x, y, d);
-	//if (camPos.z < camera.minDepth) return;
-	//if (camPos.z > camera.maxDepth) return;
-	const float2 screenPos = camera.camToScreen<float2>(camPos);
+		if (screenPos.x < in.width() && screenPos.y < in.height()) {
+			const auto input = in.tex2D(screenPos.x, screenPos.y);
+			float weight = depthMatching(params, camPos.z, camera.maxDepth);
+			const B weighted = make<B>(input) * weight;
 
-	// Not on screen so stop now...
-	if (screenPos.x >= in.width() || screenPos.y >= in.height()) return;
-    
-	const float d2 = camera.maxDepth;
-
-	const auto input = in.tex2D(screenPos.x, screenPos.y); //generateInput(in.tex2D((int)screenPos.x, (int)screenPos.y), params, worldPos);
-
-	float weight = ftl::cuda::weighting(fabs(camPos.z - d2), 0.02f);
-	const B weighted = make<B>(input) * weight;
-
-	if (weight > 0.0f) {
-		accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
-		//out(screenPos.x, screenPos.y) = input;
+			if (weight > 0.0f) {
+				accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
+			}
+		}
 	}
 }
 
diff --git a/components/renderers/cpp/src/screen.cu b/components/renderers/cpp/src/screen.cu
index e9cd06f4145c7cb2fd4947387f711af376c68912..1197f875fa7b0ca5a1649ceaecc70f0670d608f9 100644
--- a/components/renderers/cpp/src/screen.cu
+++ b/components/renderers/cpp/src/screen.cu
@@ -45,7 +45,7 @@ __device__ inline uint2 convertToScreen<ViewPortMode::Warping>(const Parameters
 		const float d = depth.tex2D(x, y);
 
 		// Find the virtual screen position of current point
-		const float3 camPos =  (d >= camera.minDepth && d <= camera.maxDepth) ? pose * camera.screenToCam(x,y,d) : make_float3(0.0f,0.0f,0.0f);
+		const float3 camPos =  (d > camera.minDepth && d < camera.maxDepth) ? pose * camera.screenToCam(x,y,d) : make_float3(0.0f,0.0f,0.0f);
 		screenPos = convertToScreen<VPMODE>(params, camPos);
 
 		if (	camPos.z < params.camera.minDepth ||
diff --git a/components/renderers/cpp/src/splatter_cuda.hpp b/components/renderers/cpp/src/splatter_cuda.hpp
index fcdcaa121c6e52994f54ecf82603edeb88f50775..95450ea36a19c1e96bd3cedcb05ffbda3f6c9d44 100644
--- a/components/renderers/cpp/src/splatter_cuda.hpp
+++ b/components/renderers/cpp/src/splatter_cuda.hpp
@@ -141,7 +141,7 @@ namespace cuda {
 
 	void show_mask(
         ftl::cuda::TextureObject<uchar4> &colour,
-		ftl::cuda::TextureObject<int> &mask,
+		ftl::cuda::TextureObject<uint8_t> &mask,
         int id, uchar4 style, cudaStream_t stream);
 
 	void merge_convert_depth(
diff --git a/components/renderers/cpp/src/triangle_render.cu b/components/renderers/cpp/src/triangle_render.cu
index df7b5dea99a5f88050016302e5df984f212bc7b9..02bc694dca8c128fb23770d3defa760d606d584a 100644
--- a/components/renderers/cpp/src/triangle_render.cu
+++ b/components/renderers/cpp/src/triangle_render.cu
@@ -132,12 +132,12 @@ __device__ void drawTriangle(const float (&d)[3], const short2 (&v)[3], const Pa
 }
 
 /**
- * Depth differences above threshold are used to determine a discontinuity and
- * hence that a triangle should not be draw between said verticies.
- * TODO: Use discontinuity mask or some better test here.
+ * This selects which triangles are drawn. It assumes that discontinuities
+ * have already been removed such that the screen coordinate alone acts to
+ * indicate a valid or invalid point.
  */
-__device__ inline bool isValidTriangle(const float (&d)[3], const Parameters &params) {
-	return !(fabs(d[0] - d[1]) > params.depthThreshold || fabs(d[0] - d[2]) > params.depthThreshold || d[0] < params.camera.minDepth || d[0] > params.camera.maxDepth);
+__device__ inline bool isValidTriangle(const short2 (&v)[3]) {
+	return v[1].x < 30000 && v[2].x < 30000;
 }
 
 /**
@@ -145,12 +145,12 @@ __device__ inline bool isValidTriangle(const float (&d)[3], const Parameters &pa
  * which verticies to load.
  */
 template <int A, int B>
-__device__ bool loadTriangle(int x, int y, float (&d)[3], short2 (&v)[3], const Parameters &params, const TextureObject<float> &depth_in, const TextureObject<short2> &screen) {
+__device__ bool loadTriangle(int x, int y, float (&d)[3], short2 (&v)[3], const TextureObject<float> &depth_in, const TextureObject<short2> &screen) {
     d[1] = depth_in.tex2D(x+A,y);
     d[2] = depth_in.tex2D(x,y+B);
     v[1] = screen.tex2D(x+A,y);
 	v[2] = screen.tex2D(x,y+B);
-	return isValidTriangle(d, params);
+	return isValidTriangle(v);
 }
 
 /*
@@ -170,11 +170,16 @@ __device__ bool loadTriangle(int x, int y, float (&d)[3], short2 (&v)[3], const
 		short2 v[3];
 		v[0] = screen.tex2D(x,y);
 
-		// Draw (optionally) 4 triangles as a diamond pattern around the central point.
-		if (loadTriangle<1,1>(x, y, d, v, params, depth_in, screen)) drawTriangle(d, v, params, depth_out);
-		if (loadTriangle<1,-1>(x, y, d, v, params, depth_in, screen)) drawTriangle(d, v, params, depth_out);
-		if (loadTriangle<-1,1>(x, y, d, v, params, depth_in, screen)) drawTriangle(d, v, params, depth_out);
-		if (loadTriangle<-1,-1>(x, y, d, v, params, depth_in, screen)) drawTriangle(d, v, params, depth_out);
+		if (v[0].x < 30000) {
+			// Calculate discontinuity threshold.
+			//const float threshold = (params.depthCoef / ((params.depthCoef / d[0]) - params.disconDisparities)) - d[0];
+
+			// Draw (optionally) 4 triangles as a diamond pattern around the central point.
+			if (loadTriangle<1,1>(x, y, d, v, depth_in, screen)) drawTriangle(d, v, params, depth_out);
+			if (loadTriangle<1,-1>(x, y, d, v, depth_in, screen)) drawTriangle(d, v, params, depth_out);
+			if (loadTriangle<-1,1>(x, y, d, v, depth_in, screen)) drawTriangle(d, v, params, depth_out);
+			if (loadTriangle<-1,-1>(x, y, d, v, depth_in, screen)) drawTriangle(d, v, params, depth_out);
+		}
 	}
 }
 
diff --git a/components/rgbd-sources/src/sources/screencapture/screencapture.cpp b/components/rgbd-sources/src/sources/screencapture/screencapture.cpp
index ef3e3badca05fabc7beda76d73c4042a9151e7cc..e96f675ba6a42bd83d221b9ff249cbfc7019bb52 100644
--- a/components/rgbd-sources/src/sources/screencapture/screencapture.cpp
+++ b/components/rgbd-sources/src/sources/screencapture/screencapture.cpp
@@ -109,6 +109,7 @@ ScreenCapture::ScreenCapture(ftl::rgbd::Source *host)
     params_.maxDepth = host_->value("depth", 1.0f);
     params_.minDepth = 0.0f;
 	params_.doffs = 0.0;
+	params_.baseline = 0.1f;
 
 	state_.getLeft() = params_;
 	state_.set("name", std::string("[ScreenCapture] ") + host_->value("name", host_->getID()));