diff --git a/CMakeLists.txt b/CMakeLists.txt
index af6a4173c4f2a08d18b2bb1f3a68336898240fa5..fb73e5cf9d35ad7de7e1a2cbf66826d802c0b749 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -225,7 +225,7 @@ add_subdirectory(components/codecs)
 add_subdirectory(components/net)
 add_subdirectory(components/rgbd-sources)
 add_subdirectory(components/control/cpp)
-add_subdirectory(components/filters)
+add_subdirectory(components/operators)
 add_subdirectory(applications/calibration)
 add_subdirectory(applications/groupview)
 add_subdirectory(applications/player)
diff --git a/applications/reconstruct/CMakeLists.txt b/applications/reconstruct/CMakeLists.txt
index 1896417ead0e05d137e818af2338e243753a059a..b089d4a1aeae9654b50865c7400ca0e381f874e6 100644
--- a/applications/reconstruct/CMakeLists.txt
+++ b/applications/reconstruct/CMakeLists.txt
@@ -36,6 +36,6 @@ set_property(TARGET ftl-reconstruct PROPERTY CUDA_SEPARABLE_COMPILATION ON)
 endif()
 
 #target_include_directories(cv-node PUBLIC ${PROJECT_SOURCE_DIR}/include)
-target_link_libraries(ftl-reconstruct ftlcommon ftlrgbd Threads::Threads ${OpenCV_LIBS} ftlctrl ftlnet ftlrender ftlfilter)
+target_link_libraries(ftl-reconstruct ftlcommon ftlrgbd Threads::Threads ${OpenCV_LIBS} ftlctrl ftlnet ftlrender ftloperators)
 
 
diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp
index a3e5504a41b11ef0f2b020710b88dae050b0d9c1..d05453f9410ee52e8c5fed610656a42f662bed93 100644
--- a/applications/reconstruct/src/main.cpp
+++ b/applications/reconstruct/src/main.cpp
@@ -30,7 +30,10 @@
 #include <opencv2/opencv.hpp>
 #include <ftl/net/universe.hpp>
 
-#include <ftl/filters/smoothing.hpp>
+#include <ftl/operators/smoothing.hpp>
+#include <ftl/operators/colours.hpp>
+#include <ftl/operators/normals.hpp>
+
 #include <ftl/cuda/normals.hpp>
 #include <ftl/registration.hpp>
 
@@ -246,11 +249,19 @@ static void run(ftl::Configurable *root) {
 
 	bool busy = false;
 
-	auto *smooth = ftl::config::create<ftl::DepthSmoother>(root, "filters");
+	// Create the source depth map pipeline
+	auto *pipeline1 = ftl::config::create<ftl::operators::Graph>(root, "pre_filters");
+	pipeline1->append<ftl::operators::ColourChannels>("colour");  // Convert BGR to BGRA
+	pipeline1->append<ftl::operators::HFSmoother>("hfnoise");  // Remove high-frequency noise
+	pipeline1->append<ftl::operators::Normals>("normals");  // Estimate surface normals
+	pipeline1->append<ftl::operators::SmoothChannel>("smoothing");  // Generate a smoothing channel
+	pipeline1->append<ftl::operators::AdaptiveMLS>("mls");  // Perform MLS (using smoothing channel)
+	// Alignment
+
 
 	group->setLatency(4);
 	group->setName("ReconGroup");
-	group->sync([splat,virt,&busy,&slave,&scene_A,&scene_B,&align,controls,smooth](ftl::rgbd::FrameSet &fs) -> bool {
+	group->sync([splat,virt,&busy,&slave,&scene_A,&scene_B,&align,controls,pipeline1](ftl::rgbd::FrameSet &fs) -> bool {
 		//cudaSetDevice(scene->getCUDADevice());
 
 		//if (slave.isPaused()) return true;
@@ -265,63 +276,17 @@ static void run(ftl::Configurable *root) {
 		// Swap the entire frameset to allow rapid return
 		fs.swapTo(scene_A);
 
-		ftl::pool.push([&scene_B,&scene_A,&busy,&slave,&align, smooth](int id) {
+		ftl::pool.push([&scene_B,&scene_A,&busy,&slave,&align, pipeline1](int id) {
 			//cudaSetDevice(scene->getCUDADevice());
 			// TODO: Release frameset here...
 			//cudaSafeCall(cudaStreamSynchronize(scene->getIntegrationStream()));
 
 			UNIQUE_LOCK(scene_A.mtx, lk);
 
-			cv::cuda::GpuMat tmp;
-			/*float factor = filter->value("smooth_factor", 0.4f);
-			float colour_limit = filter->value("colour_limit", 30.0f);
-			bool do_smooth = filter->value("pre_smooth", false);
-			int iters = filter->value("iterations", 3);
-			int radius = filter->value("radius", 5);
-			float var_thesh = filter->value("variance_threshold", 0.02f);*/
-
-			//if (do_smooth) {
-				// Presmooth...
-				for (int i=0; i<scene_A.frames.size(); ++i) {
-					auto &f = scene_A.frames[i];
-					auto s = scene_A.sources[i];
-
-					// Convert colour from BGR to BGRA if needed
-					if (f.get<cv::cuda::GpuMat>(Channel::Colour).type() == CV_8UC3) {
-						//cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
-						// Convert to 4 channel colour
-						auto &col = f.get<cv::cuda::GpuMat>(Channel::Colour);
-						tmp.create(col.size(), CV_8UC4);
-						cv::cuda::swap(col, tmp);
-						cv::cuda::cvtColor(tmp,col, cv::COLOR_BGR2BGRA, 0);
-					}
-
-					smooth->smooth(f, s);
-
-					/*ftl::cuda::smoothing_factor(
-						f.createTexture<float>(Channel::Depth),
-						f.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-						f.createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-						//f.createTexture<uchar4>(Channel::Colour),
-						f.createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-						var_thesh,
-						s->parameters(), 0
-					);*/
-
-					/*ftl::cuda::depth_smooth(
-						f.createTexture<float>(Channel::Depth),
-						f.createTexture<uchar4>(Channel::Colour),
-						f.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-						s->parameters(),
-						radius, factor, colour_limit, iters, 0
-					);*/
-				}
-			//}
-
-			// Send all frames to GPU, block until done?
-			//scene_A.upload(Channel::Colour + Channel::Depth);  // TODO: (Nick) Add scene stream.
+			pipeline1->apply(scene_A, scene_A, 0);
 			align->process(scene_A);
 
+
 			// TODO: To use second GPU, could do a download, swap, device change,
 			// then upload to other device. Or some direct device-2-device copy.
 			scene_A.swapTo(scene_B);
diff --git a/components/codecs/src/nvpipe_encoder.cpp b/components/codecs/src/nvpipe_encoder.cpp
index 10901ef56993f25960cadd0e6f17778093f256a7..132a3209ad0849dd76f1a5f7438eba8f5655b854 100644
--- a/components/codecs/src/nvpipe_encoder.cpp
+++ b/components/codecs/src/nvpipe_encoder.cpp
@@ -59,6 +59,11 @@ bool NvPipeEncoder::encode(const cv::cuda::GpuMat &in, definition_t odefinition,
 	auto width = ftl::codecs::getWidth(definition);
 	auto height = ftl::codecs::getHeight(definition);
 
+	if (in.empty()) {
+		LOG(WARNING) << "No data";
+		return false;
+	}
+
 	cv::cuda::GpuMat tmp;
 	if (width != in.cols || height != in.rows) {
 		LOG(WARNING) << "Mismatch resolution with encoding resolution";
diff --git a/components/common/cpp/include/ftl/cuda_common.hpp b/components/common/cpp/include/ftl/cuda_common.hpp
index 70a6a4ad6d4dc0def715979f9eaf348e621d103e..116e26ec74ff4b469e8d1214cafa2897264f80ad 100644
--- a/components/common/cpp/include/ftl/cuda_common.hpp
+++ b/components/common/cpp/include/ftl/cuda_common.hpp
@@ -102,6 +102,9 @@ class TextureObject : public TextureObjectBase {
 
 	operator cv::cuda::GpuMat();
 
+	void create(const cv::Size &);
+	void create(int w, int h);
+
 	__host__ __device__ T *devicePtr() const { return (T*)(ptr_); };
 	__host__ __device__ T *devicePtr(int v) const { return &(T*)(ptr_)[v*pitch2_]; }
 
@@ -264,6 +267,20 @@ TextureObject<T>::TextureObject(size_t width, size_t height) {
 	//needsdestroy_ = true;
 }
 
+#ifndef __CUDACC__
+template <typename T>
+void TextureObject<T>::create(const cv::Size &s) {
+	create(s.width, s.height);
+}
+
+template <typename T>
+void TextureObject<T>::create(int w, int h) {
+	if (width_ != w || height_ != h) {
+		*this = std::move(TextureObject<T>(w, h));
+	}
+}
+#endif
+
 template <typename T>
 TextureObject<T>::TextureObject(const TextureObject<T> &p) {
 	texobj_ = p.texobj_;
diff --git a/components/filters/include/ftl/filters/smoothing.hpp b/components/filters/include/ftl/filters/smoothing.hpp
deleted file mode 100644
index 5e5035f58981107d94f20ad948afe80297254edb..0000000000000000000000000000000000000000
--- a/components/filters/include/ftl/filters/smoothing.hpp
+++ /dev/null
@@ -1,25 +0,0 @@
-#ifndef _FTL_SMOOTHING_HPP_
-#define _FTL_SMOOTHING_HPP_
-
-#include <ftl/configurable.hpp>
-#include <ftl/cuda_common.hpp>
-#include <ftl/rgbd/source.hpp>
-#include <ftl/rgbd/frame.hpp>
-
-namespace ftl {
-
-class DepthSmoother : public ftl::Configurable {
-    public:
-    explicit DepthSmoother(nlohmann::json &config);
-    ~DepthSmoother();
-
-    void smooth(ftl::rgbd::Frame &frame, ftl::rgbd::Source *src);
-
-    private:
-    cv::cuda::GpuMat temp_;
-    ftl::rgbd::Frame frames_[4];
-};
-
-}
-
-#endif  // _FTL_SMOOTHING_HPP_
diff --git a/components/filters/src/smoothing.cpp b/components/filters/src/smoothing.cpp
deleted file mode 100644
index edd6a072fbb51cc498b243c8530f3abdb550e592..0000000000000000000000000000000000000000
--- a/components/filters/src/smoothing.cpp
+++ /dev/null
@@ -1,55 +0,0 @@
-#include <ftl/filters/smoothing.hpp>
-#include "smoothing_cuda.hpp"
-
-using ftl::DepthSmoother;
-using ftl::codecs::Channel;
-using cv::cuda::GpuMat;
-
-DepthSmoother::DepthSmoother(nlohmann::json &config) : ftl::Configurable(config) {
-
-}
-
-DepthSmoother::~DepthSmoother() {
-
-}
-
-void DepthSmoother::smooth(ftl::rgbd::Frame &f, ftl::rgbd::Source *s) {
-    float var_thresh = value("variance_threshold", 0.0002f);
-    bool do_smooth = value("pre_smooth", false);
-    int levels = max(0, min(value("levels",0), 4));
-    int iters = value("iterations",5);
-
-    if (!do_smooth) return;
-
-    for (int i=0; i<iters; ++i) {
-        ftl::cuda::smoothing_factor(
-            f.createTexture<float>(Channel::Depth),
-            f.createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-            f.createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())),
-            var_thresh,
-            s->parameters(), 0
-        );
-    }
-
-    LOG(INFO) << "PARAMS DEPTHS  " << s->parameters().minDepth << "," << s->parameters().maxDepth;
-
-    for (int i=0; i<levels; ++i) {
-        var_thresh *= 2.0f;
-        auto &dmat = f.get<GpuMat>(Channel::Depth); 
-        cv::cuda::resize(dmat, frames_[i].create<GpuMat>(Channel::Depth), cv::Size(dmat.cols / (2*(i+1)), dmat.rows / (2*(i+1))), 0.0, 0.0, cv::INTER_NEAREST);
-
-        ftl::cuda::smoothing_factor(
-            frames_[i].createTexture<float>(Channel::Depth),
-            frames_[i].createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(frames_[i].get<GpuMat>(Channel::Depth).size())),
-            frames_[i].createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(frames_[i].get<GpuMat>(Channel::Depth).size())),
-            var_thresh,
-            s->parameters(), 0
-        );
-
-        cv::cuda::resize(frames_[i].get<GpuMat>(Channel::Smoothing), temp_, f.get<cv::cuda::GpuMat>(Channel::Depth).size(), 0.0, 0.0, cv::INTER_LINEAR);
-        cv::cuda::add(temp_, f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Smoothing));
-    }
-
-    //cv::cuda::subtract(f.get<GpuMat>(Channel::Depth), f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Depth));
-}
-
diff --git a/components/filters/src/smoothing_cuda.hpp b/components/filters/src/smoothing_cuda.hpp
deleted file mode 100644
index da800f883f2e39a44253929fbc7675360e3a543d..0000000000000000000000000000000000000000
--- a/components/filters/src/smoothing_cuda.hpp
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef _FTL_CUDA_SMOOTHING_HPP_
-#define _FTL_CUDA_SMOOTHING_HPP_
-
-#include <ftl/rgbd/camera.hpp>
-#include <ftl/cuda_common.hpp>
-
-namespace ftl {
-namespace cuda {
-
-void depth_smooth(
-	ftl::cuda::TextureObject<float> &depth_in,
-	ftl::cuda::TextureObject<uchar4> &colour_in,
-	ftl::cuda::TextureObject<float> &depth_out,
-	const ftl::rgbd::Camera &camera,
-	int radius, float factor, float thresh, int iters,
-	cudaStream_t stream);
-
-void smoothing_factor(
-	ftl::cuda::TextureObject<float> &depth_in,
-	//ftl::cuda::TextureObject<float> &depth_tmp,
-	ftl::cuda::TextureObject<float> &temp,
-	//ftl::cuda::TextureObject<uchar4> &colour_in,
-	ftl::cuda::TextureObject<float> &smoothing,
-	float thresh,
-	const ftl::rgbd::Camera &camera,
-	cudaStream_t stream);
-
-}
-}
-
-#endif  // _FTL_CUDA_SMOOTHING_HPP_
diff --git a/components/filters/CMakeLists.txt b/components/operators/CMakeLists.txt
similarity index 52%
rename from components/filters/CMakeLists.txt
rename to components/operators/CMakeLists.txt
index 92601b3714ac5e166d4e4f8eecf22c8f04edc58f..c93a87f6693334c30e28039387db45554ebdb0d2 100644
--- a/components/filters/CMakeLists.txt
+++ b/components/operators/CMakeLists.txt
@@ -1,16 +1,21 @@
-add_library(ftlfilter
+add_library(ftloperators
     src/smoothing.cpp
-    src/smoothing.cu
+	src/smoothing.cu
+	src/mls.cu
+	src/smoothchan.cu
+	src/operator.cpp
+	src/colours.cpp
+	src/normals.cpp
 )
 
 # These cause errors in CI build and are being removed from PCL in newer versions
 # target_compile_options(ftlrender PUBLIC ${PCL_DEFINITIONS})
 
-target_include_directories(ftlfilter PUBLIC
+target_include_directories(ftloperators PUBLIC
 	${PCL_INCLUDE_DIRS}
 	$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
 	$<INSTALL_INTERFACE:include>
 	PRIVATE src)
-target_link_libraries(ftlfilter ftlrender ftlrgbd ftlcommon Eigen3::Eigen Threads::Threads ${OpenCV_LIBS})
+target_link_libraries(ftloperators ftlrender ftlrgbd ftlcommon Eigen3::Eigen Threads::Threads ${OpenCV_LIBS})
 
 #ADD_SUBDIRECTORY(test)
diff --git a/components/operators/include/ftl/operators/colours.hpp b/components/operators/include/ftl/operators/colours.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..afad434d49e170ba6f48d4b875d5641bdff61a54
--- /dev/null
+++ b/components/operators/include/ftl/operators/colours.hpp
@@ -0,0 +1,25 @@
+#ifndef _FTL_OPERATORS_COLOURS_HPP_
+#define _FTL_OPERATORS_COLOURS_HPP_
+
+#include <ftl/operators/operator.hpp>
+
+namespace ftl {
+namespace operators {
+
+class ColourChannels : public ftl::operators::Operator {
+    public:
+    explicit ColourChannels(ftl::Configurable *cfg);
+    ~ColourChannels();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+    private:
+    cv::cuda::GpuMat temp_;
+};
+
+}
+}
+
+#endif // _FTL_OPERATORS_COLOURS_HPP_
diff --git a/components/operators/include/ftl/operators/normals.hpp b/components/operators/include/ftl/operators/normals.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..5aff09e4da3b5867a77631c81750c42a6c23fdbd
--- /dev/null
+++ b/components/operators/include/ftl/operators/normals.hpp
@@ -0,0 +1,45 @@
+#ifndef _FTL_OPERATORS_NORMALS_HPP_
+#define _FTL_OPERATORS_NORMALS_HPP_
+
+#include <ftl/operators/operator.hpp>
+#include <ftl/cuda_common.hpp>
+
+namespace ftl {
+namespace operators {
+
+/**
+ * Calculate rough normals from local depth gradients.
+ */
+class Normals : public ftl::operators::Operator {
+	public:
+    explicit Normals(ftl::Configurable*);
+    ~Normals();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+};
+
+/**
+ * Calculate rough normals from local depth gradients and perform a weighted
+ * smoothing over the neighbourhood.
+ */
+class SmoothNormals : public ftl::operators::Operator {
+	public:
+    explicit SmoothNormals(ftl::Configurable*);
+    ~SmoothNormals();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+	private:
+	ftl::cuda::TextureObject<float4> temp_;
+
+};
+
+}
+}
+
+#endif  // _FTL_OPERATORS_NORMALS_HPP_
diff --git a/components/operators/include/ftl/operators/operator.hpp b/components/operators/include/ftl/operators/operator.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..fe9b52f2c6b7d6d3364c1d1722f70bd691602170
--- /dev/null
+++ b/components/operators/include/ftl/operators/operator.hpp
@@ -0,0 +1,117 @@
+#ifndef _FTL_OPERATORS_OPERATOR_HPP_
+#define _FTL_OPERATORS_OPERATOR_HPP_
+
+#include <list>
+#include <ftl/configurable.hpp>
+#include <ftl/configuration.hpp>
+#include <ftl/rgbd/frame.hpp>
+#include <ftl/rgbd/frameset.hpp>
+#include <ftl/rgbd/source.hpp>
+#include <ftl/cuda_common.hpp>
+
+namespace ftl {
+namespace operators {
+
+/**
+ * An abstract frame operator interface. Any kind of filter that operates on a
+ * single frame should use this as a base class. An example of a filter would
+ * be MLS smoothing, or optical flow temporal smoothing. Some 'filters' might
+ * simply generate additional channels, such as a 'Normals' filter that
+ * generates a normals channel. Filters may also have internal data buffers,
+ * these may also persist between frames in some cases.
+ */
+class Operator {
+	public:
+	explicit Operator(ftl::Configurable *cfg);
+    virtual ~Operator();
+
+	enum class Type {
+		OneToOne,		// Frame to Frame (Filter or generator)
+		ManyToOne,		// FrameSet to Frame (Rendering or Compositing)
+		ManyToMany,		// FrameSet to FrameSet (alignment)
+		OneToMany		// Currently not used or supported
+	};
+
+	/**
+	 * Must be implemented and return an operator structural type.
+	 */
+	virtual Type type() const =0;
+
+	virtual bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream);
+	virtual bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream);
+	virtual bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *os, cudaStream_t stream);
+
+	inline void enable() { enabled_ = true; }
+	inline void disable() { enabled_ = false; }
+	inline bool enabled() const { return enabled_; }
+	inline void enabled(bool e) { enabled_ = e; }
+
+	inline ftl::Configurable *config() const { return config_; }
+
+	private:
+	bool enabled_;
+	ftl::Configurable *config_;
+};
+
+namespace detail {
+
+struct ConstructionHelperBase {
+	ConstructionHelperBase(ftl::Configurable *cfg) : config(cfg) {}
+	virtual ~ConstructionHelperBase() {}
+	virtual ftl::operators::Operator *make()=0;
+
+	ftl::Configurable *config;
+};
+
+template <typename T>
+struct ConstructionHelper : public ConstructionHelperBase {
+	ConstructionHelper(ftl::Configurable *cfg) : ConstructionHelperBase(cfg) {}
+	~ConstructionHelper() {}
+	ftl::operators::Operator *make() override {
+		return new T(config);
+	}
+};
+
+struct OperatorNode {
+	ConstructionHelperBase *maker;
+	std::vector<ftl::operators::Operator*> instances;
+};
+
+}
+
+/**
+ * Represent a sequential collection of operators. Each operator created is
+ * added to an internal list and then applied to a frame in the order they were
+ * created. A directed acyclic graph can also be formed.
+ */
+class Graph : public ftl::Configurable {
+	public:
+	explicit Graph(nlohmann::json &config);
+    ~Graph();
+
+	template <typename T>
+	ftl::Configurable *append(const std::string &name);
+
+	bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream=0);
+	bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream=0);
+	bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream=0);
+
+	private:
+	std::list<ftl::operators::detail::OperatorNode> operators_;
+	std::map<std::string, ftl::Configurable*> configs_;
+
+	ftl::Configurable *_append(ftl::operators::detail::ConstructionHelperBase*);
+};
+
+}
+}
+
+template <typename T>
+ftl::Configurable *ftl::operators::Graph::append(const std::string &name) {
+	if (configs_.find(name) == configs_.end()) {
+		configs_[name] = ftl::create<ftl::Configurable>(this, name);
+	}
+	return _append(new ftl::operators::detail::ConstructionHelper<T>(configs_[name]));
+}
+
+#endif  // _FTL_OPERATORS_OPERATOR_HPP_
diff --git a/components/operators/include/ftl/operators/smoothing.hpp b/components/operators/include/ftl/operators/smoothing.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..b5362ea6f1a6c16de81cdb7c55339058476da09d
--- /dev/null
+++ b/components/operators/include/ftl/operators/smoothing.hpp
@@ -0,0 +1,104 @@
+#ifndef _FTL_OPERATORS_SMOOTHING_HPP_
+#define _FTL_OPERATORS_SMOOTHING_HPP_
+
+#include <ftl/operators/operator.hpp>
+
+namespace ftl {
+namespace operators {
+
+/**
+ * Remove high frequency noise whilst attempting to retain sharp edges and curves.
+ * It uses the minimum error in the second derivative of the local surface as
+ * a smoothing factor, with the depth error itself taken from the minimum
+ * first derivative. Only the depth channel is used and modified.
+ */
+class HFSmoother : public ftl::operators::Operator {
+    public:
+    explicit HFSmoother(ftl::Configurable*);
+    ~HFSmoother();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+    private:
+    cv::cuda::GpuMat temp_;
+    ftl::rgbd::Frame frames_[4];
+};
+
+/**
+ * Generate a smoothing channel from the colour image that provides a smoothing
+ * factor for each pixel. It uses colour gradient at multiple resolutions to
+ * decide on how much a given pixel needs smoothing, large single colour areas
+ * will generate a large smoothing value, whilst sharp colour edges will have
+ * no smoothing.
+ */
+class SmoothChannel : public ftl::operators::Operator {
+    public:
+    explicit SmoothChannel(ftl::Configurable*);
+    ~SmoothChannel();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+	private:
+	ftl::rgbd::Frame temp_[6];
+};
+
+/**
+ * Perform Moving Least Squares smoothing with a constant smoothing amount and
+ * neighbourhood size. Requires channels: Depth + Normals.
+ * Also outputs Depth + Normals.
+ */
+class SimpleMLS : public ftl::operators::Operator {
+    public:
+    explicit SimpleMLS(ftl::Configurable*);
+    ~SimpleMLS();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+    private:
+};
+
+/**
+ * Perform Moving Least Squares smoothing with a smoothing amount determined
+ * by a simple colour similarity weighting. In practice this is too naive.
+ */
+class ColourMLS : public ftl::operators::Operator {
+    public:
+    explicit ColourMLS(ftl::Configurable*);
+    ~ColourMLS();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+    private:
+};
+
+/**
+ * A version of Moving Least Squares where both the smoothing factor and
+ * neighbourhood size are adapted over an extra large range using the colour
+ * channel as a guide. Requires Depth+Normals+Colour. Neighbourhood can
+ * encompass hundreds of pixels with a smoothing factor approaching a meter, or
+ * it can be only a few or even no pixels with a zero smoothing factor.
+ */
+class AdaptiveMLS : public ftl::operators::Operator {
+    public:
+    explicit AdaptiveMLS(ftl::Configurable*);
+    ~AdaptiveMLS();
+
+	inline Operator::Type type() const override { return Operator::Type::OneToOne; }
+
+    bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override;
+
+    private:
+};
+
+}
+}
+
+#endif  // _FTL_OPERATORS_SMOOTHING_HPP_
diff --git a/components/operators/src/colours.cpp b/components/operators/src/colours.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..3174c42e41de75e30f852c5bb187266ad26b61aa
--- /dev/null
+++ b/components/operators/src/colours.cpp
@@ -0,0 +1,26 @@
+#include <ftl/operators/colours.hpp>
+
+using ftl::operators::ColourChannels;
+using ftl::codecs::Channel;
+
+ColourChannels::ColourChannels(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+ColourChannels::~ColourChannels() {
+
+}
+
+bool ColourChannels::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	// Convert colour from BGR to BGRA if needed
+	if (in.get<cv::cuda::GpuMat>(Channel::Colour).type() == CV_8UC3) {
+		//cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
+		// Convert to 4 channel colour
+		auto &col = in.get<cv::cuda::GpuMat>(Channel::Colour);
+		temp_.create(col.size(), CV_8UC4);
+		cv::cuda::swap(col, temp_);
+		cv::cuda::cvtColor(temp_,col, cv::COLOR_BGR2BGRA, 0);
+	}
+
+	return true;
+}
diff --git a/components/operators/src/mls.cu b/components/operators/src/mls.cu
new file mode 100644
index 0000000000000000000000000000000000000000..e030d1967695bd71760c0bc2af26706d21f0f2e3
--- /dev/null
+++ b/components/operators/src/mls.cu
@@ -0,0 +1,314 @@
+#include "smoothing_cuda.hpp"
+
+#include <ftl/cuda/weighting.hpp>
+
+using ftl::cuda::TextureObject;
+
+#define T_PER_BLOCK 8
+
+// ===== MLS Smooth ============================================================
+
+/*
+ * Smooth depth map using Moving Least Squares
+ */
+ template <int SEARCH_RADIUS>
+ __global__ void mls_smooth_kernel(
+		TextureObject<float4> normals_in,
+		TextureObject<float4> normals_out,
+        TextureObject<float> depth_in,        // Virtual depth map
+		TextureObject<float> depth_out,   // Accumulated output
+		float smoothing,
+        ftl::rgbd::Camera camera) {
+        
+    const int x = blockIdx.x*blockDim.x + threadIdx.x;
+    const int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+    if (x < 0 || y < 0 || x >= depth_in.width() || y >= depth_in.height()) return;
+
+	float3 aX = make_float3(0.0f,0.0f,0.0f);
+	float3 nX = make_float3(0.0f,0.0f,0.0f);
+    float contrib = 0.0f;
+
+	float d0 = depth_in.tex2D(x, y);
+	depth_out(x,y) = d0;
+	if (d0 < camera.minDepth || d0 > camera.maxDepth) return;
+	float3 X = camera.screenToCam((int)(x),(int)(y),d0);
+
+    // Neighbourhood
+    for (int v=-SEARCH_RADIUS; v<=SEARCH_RADIUS; ++v) {
+    for (int u=-SEARCH_RADIUS; u<=SEARCH_RADIUS; ++u) {
+		const float d = depth_in.tex2D(x+u, y+v);
+		if (d < camera.minDepth || d > camera.maxDepth) continue;
+
+		// Point and normal of neighbour
+		const float3 Xi = camera.screenToCam((int)(x)+u,(int)(y)+v,d);
+		const float3 Ni = make_float3(normals_in.tex2D((int)(x)+u, (int)(y)+v));
+
+		// Gauss approx weighting function using point distance
+		const float w = ftl::cuda::spatialWeighting(X,Xi,smoothing);
+
+		aX += Xi*w;
+		nX += Ni*w;
+		contrib += w;
+    }
+	}
+	
+	nX /= contrib;  // Weighted average normal
+	aX /= contrib;  // Weighted average point (centroid)
+
+	// Signed-Distance Field function
+	float fX = nX.x * (X.x - aX.x) + nX.y * (X.y - aX.y) + nX.z * (X.z - aX.z);
+
+	// Calculate new point using SDF function to adjust depth (and position)
+	X = X - nX * fX;
+	
+	//uint2 screen = camera.camToScreen<uint2>(X);
+
+    //if (screen.x < depth_out.width() && screen.y < depth_out.height()) {
+    //    depth_out(screen.x,screen.y) = X.z;
+	//}
+	depth_out(x,y) = X.z;
+	normals_out(x,y) = make_float4(nX / length(nX), 0.0f);
+}
+
+void ftl::cuda::mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		float smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream) {
+
+	const dim3 gridSize((depth_out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth_out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	switch (radius) {
+		case 5: mls_smooth_kernel<5><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 4: mls_smooth_kernel<4><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 3: mls_smooth_kernel<3><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 2: mls_smooth_kernel<2><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 1: mls_smooth_kernel<1><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+	}
+	cudaSafeCall( cudaGetLastError() );
+
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	#endif
+}
+
+
+// ===== Colour MLS Smooth =====================================================
+
+/*
+ * Smooth depth map using Moving Least Squares. This version uses colour
+ * similarity weights to adjust the spatial smoothing factor. It is naive in
+ * that similar colours may exist on both sides of an edge and colours at the
+ * level of single pixels can be subject to noise. Colour noise should first
+ * be removed from the image.
+ */
+ template <int SEARCH_RADIUS>
+ __global__ void colour_mls_smooth_kernel(
+		TextureObject<float4> normals_in,
+		TextureObject<float4> normals_out,
+        TextureObject<float> depth_in,        // Virtual depth map
+		TextureObject<float> depth_out,   // Accumulated output
+		TextureObject<uchar4> colour_in,
+		float smoothing,
+		float colour_smoothing,
+        ftl::rgbd::Camera camera) {
+        
+    const int x = blockIdx.x*blockDim.x + threadIdx.x;
+    const int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+    if (x < 0 || y < 0 || x >= depth_in.width() || y >= depth_in.height()) return;
+
+	float3 aX = make_float3(0.0f,0.0f,0.0f);
+	float3 nX = make_float3(0.0f,0.0f,0.0f);
+    float contrib = 0.0f;
+
+	float d0 = depth_in.tex2D(x, y);
+	depth_out(x,y) = d0;
+	if (d0 < camera.minDepth || d0 > camera.maxDepth) return;
+	float3 X = camera.screenToCam((int)(x),(int)(y),d0);
+
+	uchar4 c0 = colour_in.tex2D(x, y);
+
+    // Neighbourhood
+    for (int v=-SEARCH_RADIUS; v<=SEARCH_RADIUS; ++v) {
+    for (int u=-SEARCH_RADIUS; u<=SEARCH_RADIUS; ++u) {
+		const float d = depth_in.tex2D(x+u, y+v);
+		if (d < camera.minDepth || d > camera.maxDepth) continue;
+
+		// Point and normal of neighbour
+		const float3 Xi = camera.screenToCam((int)(x)+u,(int)(y)+v,d);
+		const float3 Ni = make_float3(normals_in.tex2D((int)(x)+u, (int)(y)+v));
+
+		const uchar4 c = colour_in.tex2D(x+u, y+v);
+		const float cw = ftl::cuda::colourWeighting(c0,c,colour_smoothing);
+
+		// Gauss approx weighting function using point distance
+		const float w = ftl::cuda::spatialWeighting(X,Xi,smoothing*cw);
+
+		aX += Xi*w;
+		nX += Ni*w;
+		contrib += w;
+    }
+	}
+	
+	nX /= contrib;  // Weighted average normal
+	aX /= contrib;  // Weighted average point (centroid)
+
+	// Signed-Distance Field function
+	float fX = nX.x * (X.x - aX.x) + nX.y * (X.y - aX.y) + nX.z * (X.z - aX.z);
+
+	// Calculate new point using SDF function to adjust depth (and position)
+	X = X - nX * fX;
+	
+	//uint2 screen = camera.camToScreen<uint2>(X);
+
+    //if (screen.x < depth_out.width() && screen.y < depth_out.height()) {
+    //    depth_out(screen.x,screen.y) = X.z;
+	//}
+	depth_out(x,y) = X.z;
+	normals_out(x,y) = make_float4(nX / length(nX), 0.0f);
+}
+
+void ftl::cuda::colour_mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		ftl::cuda::TextureObject<uchar4> &colour_in,
+		float smoothing,
+		float colour_smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream) {
+
+	const dim3 gridSize((depth_out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth_out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	switch (radius) {
+		case 5: colour_mls_smooth_kernel<5><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, colour_in, smoothing, colour_smoothing, camera); break;
+		case 4: colour_mls_smooth_kernel<4><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, colour_in, smoothing, colour_smoothing, camera); break;
+		case 3: colour_mls_smooth_kernel<3><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, colour_in, smoothing, colour_smoothing, camera); break;
+		case 2: colour_mls_smooth_kernel<2><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, colour_in, smoothing, colour_smoothing, camera); break;
+		case 1: colour_mls_smooth_kernel<1><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, colour_in, smoothing, colour_smoothing, camera); break;
+	}
+	cudaSafeCall( cudaGetLastError() );
+
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	#endif
+}
+
+
+// ===== Adaptive MLS Smooth =====================================================
+
+/*
+ * Smooth depth map using Moving Least Squares. This version uses colour
+ * similarity weights to adjust the spatial smoothing factor. It is naive in
+ * that similar colours may exist on both sides of an edge and colours at the
+ * level of single pixels can be subject to noise. Colour noise should first
+ * be removed from the image.
+ */
+ template <int SEARCH_RADIUS>
+ __global__ void adaptive_mls_smooth_kernel(
+		TextureObject<float4> normals_in,
+		TextureObject<float4> normals_out,
+        TextureObject<float> depth_in,        // Virtual depth map
+		TextureObject<float> depth_out,   // Accumulated output
+		TextureObject<float> smoothing,
+        ftl::rgbd::Camera camera) {
+        
+    const int x = blockIdx.x*blockDim.x + threadIdx.x;
+    const int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+    if (x < 0 || y < 0 || x >= depth_in.width() || y >= depth_in.height()) return;
+
+	float3 aX = make_float3(0.0f,0.0f,0.0f);
+	float3 nX = make_float3(0.0f,0.0f,0.0f);
+    float contrib = 0.0f;
+
+	float d0 = depth_in.tex2D(x, y);
+	depth_out(x,y) = d0;
+	normals_out(x,y) = normals_in(x,y);
+	if (d0 < camera.minDepth || d0 > camera.maxDepth) return;
+	float3 X = camera.screenToCam((int)(x),(int)(y),d0);
+
+	//uchar4 c0 = colour_in.tex2D(x, y);
+	float smooth = smoothing(x,y);
+
+    // Neighbourhood
+    for (int v=-SEARCH_RADIUS; v<=SEARCH_RADIUS; ++v) {
+    for (int u=-SEARCH_RADIUS; u<=SEARCH_RADIUS; ++u) {
+		const float d = depth_in.tex2D(x+u, y+v);
+		if (d < camera.minDepth || d > camera.maxDepth) continue;
+
+		// Point and normal of neighbour
+		const float3 Xi = camera.screenToCam((int)(x)+u,(int)(y)+v,d);
+		const float3 Ni = make_float3(normals_in.tex2D((int)(x)+u, (int)(y)+v));
+
+		if (Ni.x+Ni.y+Ni.z == 0.0f) continue;
+
+		// Gauss approx weighting function using point distance
+		const float w = ftl::cuda::spatialWeighting(X,Xi,smooth*0.5f);
+
+		aX += Xi*w;
+		nX += Ni*w;
+		contrib += w;
+    }
+	}
+
+	if (contrib <= 0.0f) return;
+	
+	nX /= contrib;  // Weighted average normal
+	aX /= contrib;  // Weighted average point (centroid)
+
+	// Signed-Distance Field function
+	float fX = nX.x * (X.x - aX.x) + nX.y * (X.y - aX.y) + nX.z * (X.z - aX.z);
+
+	// Calculate new point using SDF function to adjust depth (and position)
+	X = X - nX * fX;
+	
+	//uint2 screen = camera.camToScreen<uint2>(X);
+
+    //if (screen.x < depth_out.width() && screen.y < depth_out.height()) {
+    //    depth_out(screen.x,screen.y) = X.z;
+	//}
+	depth_out(x,y) = X.z;
+	normals_out(x,y) = make_float4(nX / length(nX), 0.0f);
+}
+
+void ftl::cuda::adaptive_mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		ftl::cuda::TextureObject<float> &smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream) {
+
+	const dim3 gridSize((depth_out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth_out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	switch (radius) {
+		case 5: adaptive_mls_smooth_kernel<5><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 4: adaptive_mls_smooth_kernel<4><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 3: adaptive_mls_smooth_kernel<3><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 2: adaptive_mls_smooth_kernel<2><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+		case 1: adaptive_mls_smooth_kernel<1><<<gridSize, blockSize, 0, stream>>>(normals_in, normals_out, depth_in, depth_out, smoothing, camera); break;
+	}
+	cudaSafeCall( cudaGetLastError() );
+
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	#endif
+}
+
diff --git a/components/operators/src/normals.cpp b/components/operators/src/normals.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..5f8554c2986f27de3fe5bd0ab2fb03fbf2226c35
--- /dev/null
+++ b/components/operators/src/normals.cpp
@@ -0,0 +1,76 @@
+#include <ftl/operators/normals.hpp>
+#include <ftl/cuda/normals.hpp>
+#include <ftl/utility/matrix_conversion.hpp>
+
+using ftl::operators::Normals;
+using ftl::operators::SmoothNormals;
+using ftl::codecs::Channel;
+using ftl::rgbd::Format;
+
+Normals::Normals(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+Normals::~Normals() {
+
+}
+
+bool Normals::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	if (!in.hasChannel(Channel::Depth)) {
+		LOG(ERROR) << "Missing depth channel in Normals operator";
+		return false;
+	}
+
+	if (out.hasChannel(Channel::Normals)) {
+		LOG(WARNING) << "Output already has normals";
+	}
+
+	ftl::cuda::normals(
+		out.createTexture<float4>(Channel::Normals, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+		in.createTexture<float>(Channel::Depth),
+		s->parameters(), 0
+	);
+
+	return true;
+}
+
+
+SmoothNormals::SmoothNormals(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+SmoothNormals::~SmoothNormals() {
+
+}
+
+bool SmoothNormals::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+    float smoothing = config()->value("normal_smoothing", 0.02f);
+    int radius = max(0, min(config()->value("radius",1), 5));
+
+	if (!in.hasChannel(Channel::Depth)) {
+		LOG(ERROR) << "Missing depth channel in SmoothNormals operator";
+		return false;
+	}
+
+	if (out.hasChannel(Channel::Normals)) {
+		LOG(WARNING) << "Output already has normals";
+	}
+
+	auto &depth = in.get<cv::cuda::GpuMat>(Channel::Depth);
+
+	temp_.create(depth.size());
+
+    ftl::cuda::normals(
+		out.createTexture<float4>(Channel::Normals, Format<float4>(depth.size())),
+		temp_,
+		in.createTexture<float>(Channel::Depth),
+		radius, smoothing,
+		s->parameters(),
+		MatrixConversion::toCUDA(s->getPose().cast<float>().inverse()).getFloat3x3(),
+		MatrixConversion::toCUDA(s->getPose().cast<float>()).getFloat3x3(),
+		stream
+	);
+
+
+	return true;
+}
diff --git a/components/operators/src/operator.cpp b/components/operators/src/operator.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..91dada28b6adddfcdb3e71861aca07591c57fa9c
--- /dev/null
+++ b/components/operators/src/operator.cpp
@@ -0,0 +1,87 @@
+#include <ftl/operators/operator.hpp>
+
+using ftl::operators::Operator;
+using ftl::operators::Graph;
+using ftl::rgbd::Frame;
+using ftl::rgbd::FrameSet;
+using ftl::rgbd::Source;
+
+Operator::Operator(ftl::Configurable *config) : config_(config) {
+	enabled_ = config_->value("enabled", true);
+
+	config_->on("enabled", [this](const ftl::config::Event &e) {
+		enabled_ = config_->value("enabled", true);
+	});
+}
+
+Operator::~Operator() {}
+
+bool Operator::apply(Frame &in, Frame &out, Source *s, cudaStream_t stream) {
+	return false;
+}
+
+bool Operator::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) {
+	return false;
+}
+
+bool Operator::apply(FrameSet &in, Frame &out, Source *os, cudaStream_t stream) {
+	return false;
+}
+
+
+
+Graph::Graph(nlohmann::json &config) : ftl::Configurable(config) {
+
+}
+
+Graph::~Graph() {
+
+}
+
+bool Graph::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) {
+	if (!value("enabled", true)) return false;
+
+	if (in.frames.size() != out.frames.size()) return false;
+
+	for (auto &i : operators_) {
+		// Make sure there are enough instances
+		while (i.instances.size() < in.frames.size()) {
+			i.instances.push_back(i.maker->make());
+		}
+
+		for (int j=0; j<in.frames.size(); ++j) {
+			auto *instance = i.instances[j];
+
+			if (instance->enabled()) {
+				instance->apply(in.frames[j], out.frames[j], in.sources[j], stream);
+			}
+		}
+	}
+
+	return true;
+}
+
+bool Graph::apply(Frame &in, Frame &out, Source *s, cudaStream_t stream) {
+	if (!value("enabled", true)) return false;
+
+	for (auto &i : operators_) {
+		// Make sure there are enough instances
+		if (i.instances.size() < 1) {
+			i.instances.push_back(i.maker->make());
+		}
+
+		auto *instance = i.instances[0];
+
+		if (instance->enabled()) {
+			instance->apply(in, out, s, stream);
+		}
+	}
+
+	return true;
+}
+
+ftl::Configurable *Graph::_append(ftl::operators::detail::ConstructionHelperBase *m) {
+	auto &o = operators_.emplace_back();
+	o.maker = m;
+	return m->config;
+}
diff --git a/components/operators/src/smoothchan.cu b/components/operators/src/smoothchan.cu
new file mode 100644
index 0000000000000000000000000000000000000000..af9ec35243ed6304f859ab16c2177aa761c8eb14
--- /dev/null
+++ b/components/operators/src/smoothchan.cu
@@ -0,0 +1,82 @@
+#include "smoothing_cuda.hpp"
+
+#include <ftl/cuda/weighting.hpp>
+
+using ftl::cuda::TextureObject;
+
+#define T_PER_BLOCK 8
+
+template <int RADIUS>
+__global__ void smooth_chan_kernel(
+		ftl::cuda::TextureObject<uchar4> colour_in,
+		//ftl::cuda::TextureObject<float> depth_in,
+		ftl::cuda::TextureObject<float> smoothing_out,
+		ftl::rgbd::Camera camera,
+		float alpha, float scale) {
+
+	const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x;
+	const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+	if (x < smoothing_out.width() && y < smoothing_out.height()) {
+		const int ix = int(((float)x / (float)smoothing_out.width()) * (float)colour_in.width());
+		const int iy = int(((float)y / (float)smoothing_out.height()) * (float)colour_in.height());
+
+		// A distance has already been found
+		if (smoothing_out(x,y) < 1.0f) return;
+
+		float mindist = 100.0f;
+
+		const uchar4 c0 = colour_in.tex2D(ix, iy);
+		//const float d0 = depth_in.tex2D(ix, iy);
+		//if (d0 < camera.minDepth || d0 > camera.maxDepth) return;
+
+		//const float3 pos = camera.screenToCam(ix, iy, d0);
+
+		for (int v=-RADIUS; v<=RADIUS; ++v) {
+			#pragma unroll
+			for (int u=-RADIUS; u<=RADIUS; ++u) {
+				const uchar4 c = colour_in.tex2D(ix+u, iy+v);
+				//const float d = depth_in.tex2D(ix+u, iy+v);
+				//if (d < camera.minDepth || d > camera.maxDepth) continue;
+				//const float3 posN = camera.screenToCam(ix+u, iy+v, d);
+
+				float d = sqrt((float)u*(float)u + (float)v*(float)v) * scale;
+
+				if (ftl::cuda::colourDistance(c, c0) >= alpha) mindist = min(mindist, (float)d);
+			}
+		}
+
+		smoothing_out(x,y) = min(mindist / 100.0f, 1.0f);
+	}
+}
+
+void ftl::cuda::smooth_channel(
+		ftl::cuda::TextureObject<uchar4> &colour_in,
+		//ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &smoothing_out,
+		const ftl::rgbd::Camera &camera,
+		float alpha,
+		float scale,
+		int radius,
+		cudaStream_t stream) {
+
+	const dim3 gridSize((smoothing_out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (smoothing_out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+
+	switch (radius) {
+		case 5: smooth_chan_kernel<5><<<gridSize, blockSize, 0, stream>>>(colour_in, smoothing_out, camera, alpha, scale); break;
+		case 4: smooth_chan_kernel<4><<<gridSize, blockSize, 0, stream>>>(colour_in, smoothing_out, camera, alpha, scale); break;
+		case 3: smooth_chan_kernel<3><<<gridSize, blockSize, 0, stream>>>(colour_in, smoothing_out, camera, alpha, scale); break;
+		case 2: smooth_chan_kernel<2><<<gridSize, blockSize, 0, stream>>>(colour_in, smoothing_out, camera, alpha, scale); break;
+		case 1: smooth_chan_kernel<1><<<gridSize, blockSize, 0, stream>>>(colour_in, smoothing_out, camera, alpha, scale); break;
+	}
+		
+
+	cudaSafeCall( cudaGetLastError() );
+
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	#endif
+}
diff --git a/components/operators/src/smoothing.cpp b/components/operators/src/smoothing.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..8e4f458bf9f996a6d38bef816ab7bcec75b69b11
--- /dev/null
+++ b/components/operators/src/smoothing.cpp
@@ -0,0 +1,253 @@
+#include <ftl/operators/smoothing.hpp>
+#include "smoothing_cuda.hpp"
+
+#include <ftl/cuda/normals.hpp>
+
+using ftl::operators::HFSmoother;
+using ftl::operators::SimpleMLS;
+using ftl::operators::ColourMLS;
+using ftl::operators::AdaptiveMLS;
+using ftl::operators::SmoothChannel;
+using ftl::codecs::Channel;
+using ftl::rgbd::Format;
+using cv::cuda::GpuMat;
+
+HFSmoother::HFSmoother(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+HFSmoother::~HFSmoother() {
+
+}
+
+bool HFSmoother::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+    float var_thresh = config()->value("variance_threshold", 0.0002f);
+    int levels = max(0, min(config()->value("levels",0), 4));
+    int iters = config()->value("iterations",5);
+
+	// FIXME: in and out are assumed to be the same
+
+    for (int i=0; i<iters; ++i) {
+        ftl::cuda::smoothing_factor(
+            in.createTexture<float>(Channel::Depth),
+            in.createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+            in.createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+            var_thresh,
+            s->parameters(), 0
+        );
+    }
+
+    //LOG(INFO) << "PARAMS DEPTHS  " << s->parameters().minDepth << "," << s->parameters().maxDepth;
+
+    /*for (int i=0; i<levels; ++i) {
+        var_thresh *= 2.0f;
+        auto &dmat = f.get<GpuMat>(Channel::Depth); 
+        cv::cuda::resize(dmat, frames_[i].create<GpuMat>(Channel::Depth), cv::Size(dmat.cols / (2*(i+1)), dmat.rows / (2*(i+1))), 0.0, 0.0, cv::INTER_NEAREST);
+
+        ftl::cuda::smoothing_factor(
+            frames_[i].createTexture<float>(Channel::Depth),
+            frames_[i].createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(frames_[i].get<GpuMat>(Channel::Depth).size())),
+            frames_[i].createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(frames_[i].get<GpuMat>(Channel::Depth).size())),
+            var_thresh,
+            s->parameters(), 0
+        );
+
+        cv::cuda::resize(frames_[i].get<GpuMat>(Channel::Smoothing), temp_, f.get<cv::cuda::GpuMat>(Channel::Depth).size(), 0.0, 0.0, cv::INTER_LINEAR);
+        cv::cuda::add(temp_, f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Smoothing));
+    }*/
+
+    //cv::cuda::subtract(f.get<GpuMat>(Channel::Depth), f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Depth));
+
+	return true;
+}
+
+// ====== Smoothing Channel ====================================================
+
+SmoothChannel::SmoothChannel(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+SmoothChannel::~SmoothChannel() {
+
+}
+
+bool SmoothChannel::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	int radius = config()->value("radius", 3);
+	float threshold = config()->value("threshold", 30.0f);
+	int iters = max(0, min(6, config()->value("levels", 4)));
+
+	int width = s->parameters().width;
+	int height = s->parameters().height;
+	float scale = 1.0f;
+
+	// Clear to max smoothing
+	out.create<GpuMat>(Channel::Smoothing, Format<float>(width, height)).setTo(cv::Scalar(1.0f));
+
+	// Reduce to nearest
+	ftl::cuda::smooth_channel(
+		in.createTexture<uchar4>(Channel::Colour),
+		//in.createTexture<float>(Channel::Depth),
+		out.createTexture<float>(Channel::Smoothing),
+		s->parameters(),
+		threshold,
+		scale,
+		radius,
+		stream
+	);
+
+	for (int i=0; i<iters; ++i) {
+		width /= 2;
+		height /= 2;
+		scale *= 2.0f;
+
+		ftl::rgbd::Camera scaledCam = s->parameters().scaled(width, height);
+
+		// Downscale images for next pass
+		cv::cuda::resize(in.get<GpuMat>(Channel::Colour), temp_[i].create<GpuMat>(Channel::Colour), cv::Size(width, height), 0.0, 0.0, cv::INTER_LINEAR);
+		//cv::cuda::resize(in.get<GpuMat>(Channel::Depth), temp_[i].create<GpuMat>(Channel::Depth), cv::Size(width, height), 0.0, 0.0, cv::INTER_NEAREST);
+
+		ftl::cuda::smooth_channel(
+			temp_[i].createTexture<uchar4>(Channel::Colour),
+			//temp_[i].createTexture<float>(Channel::Depth),
+			out.getTexture<float>(Channel::Smoothing),
+			scaledCam,
+			threshold,
+			scale,
+			radius,
+			stream
+		);
+	}
+
+	return true;
+}
+
+
+
+// ===== MLS ===================================================================
+
+SimpleMLS::SimpleMLS(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+SimpleMLS::~SimpleMLS() {
+
+}
+
+bool SimpleMLS::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	float thresh = config()->value("mls_threshold", 0.04f);
+	int iters = config()->value("mls_iterations", 1);
+	int radius = config()->value("mls_radius",2);
+
+	if (!in.hasChannel(Channel::Normals)) {
+		/*ftl::cuda::normals(
+			in.createTexture<float4>(Channel::Normals, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<float>(Channel::Depth),
+			s->parameters(), 0
+		);*/
+		LOG(ERROR) << "Required normals channel missing for MLS";
+		return false;
+	}
+
+	// FIXME: Assume in and out are the same frame.
+	for (int i=0; i<iters; ++i) {
+		ftl::cuda::mls_smooth(
+			in.createTexture<float4>(Channel::Normals),
+			in.createTexture<float4>(Channel::Points, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<float>(Channel::Depth),
+			in.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			thresh,
+			radius,
+			s->parameters(),
+			0
+		);
+
+		in.swapChannels(Channel::Depth, Channel::Depth2);
+		in.swapChannels(Channel::Normals, Channel::Points);
+	}
+
+	return true;
+}
+
+
+
+ColourMLS::ColourMLS(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+ColourMLS::~ColourMLS() {
+
+}
+
+bool ColourMLS::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	float thresh = config()->value("mls_threshold", 0.04f);
+	float col_smooth = config()->value("mls_colour_smoothing", 30.0f);
+	int iters = config()->value("mls_iterations", 1);
+	int radius = config()->value("mls_radius",2);
+
+	if (!in.hasChannel(Channel::Normals)) {
+		LOG(ERROR) << "Required normals channel missing for MLS";
+		return false;
+	}
+
+	// FIXME: Assume in and out are the same frame.
+	for (int i=0; i<iters; ++i) {
+		ftl::cuda::colour_mls_smooth(
+			in.createTexture<float4>(Channel::Normals),
+			in.createTexture<float4>(Channel::Points, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<float>(Channel::Depth),
+			in.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<uchar4>(Channel::Colour),
+			thresh,
+			col_smooth,
+			radius,
+			s->parameters(),
+			0
+		);
+
+		in.swapChannels(Channel::Depth, Channel::Depth2);
+		in.swapChannels(Channel::Normals, Channel::Points);
+	}
+
+	return true;
+}
+
+
+// ====== Adaptive MLS =========================================================
+
+AdaptiveMLS::AdaptiveMLS(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
+
+}
+
+AdaptiveMLS::~AdaptiveMLS() {
+
+}
+
+bool AdaptiveMLS::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) {
+	int iters = config()->value("mls_iterations", 1);
+	int radius = config()->value("mls_radius",2);
+
+	if (!in.hasChannel(Channel::Normals)) {
+		LOG(ERROR) << "Required normals channel missing for MLS";
+		return false;
+	}
+
+	// FIXME: Assume in and out are the same frame.
+	for (int i=0; i<iters; ++i) {
+		ftl::cuda::adaptive_mls_smooth(
+			in.createTexture<float4>(Channel::Normals),
+			in.createTexture<float4>(Channel::Points, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<float>(Channel::Depth),
+			in.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())),
+			in.createTexture<float>(Channel::Smoothing),
+			radius,
+			s->parameters(),
+			0
+		);
+
+		in.swapChannels(Channel::Depth, Channel::Depth2);
+		in.swapChannels(Channel::Normals, Channel::Points);
+	}
+
+	return true;
+}
+
diff --git a/components/filters/src/smoothing.cu b/components/operators/src/smoothing.cu
similarity index 99%
rename from components/filters/src/smoothing.cu
rename to components/operators/src/smoothing.cu
index 43cb1f6bd0a56760aa2c6d4d3fff4c664631c404..a2b7377fba011243c08cf5347f3dea4800b8ab51 100644
--- a/components/filters/src/smoothing.cu
+++ b/components/operators/src/smoothing.cu
@@ -6,6 +6,8 @@ using ftl::cuda::TextureObject;
 
 #define T_PER_BLOCK 8
 
+// ===== Colour-based Smooth ===================================================
+
 template <int RADIUS>
 __global__ void depth_smooth_kernel(
 		ftl::cuda::TextureObject<float> depth_in,
diff --git a/components/operators/src/smoothing_cuda.hpp b/components/operators/src/smoothing_cuda.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..53e8cf898c4e99875dc4a9881df58700ee31c127
--- /dev/null
+++ b/components/operators/src/smoothing_cuda.hpp
@@ -0,0 +1,73 @@
+#ifndef _FTL_CUDA_SMOOTHING_HPP_
+#define _FTL_CUDA_SMOOTHING_HPP_
+
+#include <ftl/rgbd/camera.hpp>
+#include <ftl/cuda_common.hpp>
+
+namespace ftl {
+namespace cuda {
+
+void mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		float smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream);
+
+void colour_mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		ftl::cuda::TextureObject<uchar4> &colour_in,
+		float smoothing,
+		float colour_smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream);
+
+void adaptive_mls_smooth(
+		ftl::cuda::TextureObject<float4> &normals_in,
+		ftl::cuda::TextureObject<float4> &normals_out,
+		ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &depth_out,
+		ftl::cuda::TextureObject<float> &smoothing,
+		int radius,
+		const ftl::rgbd::Camera &camera,
+		cudaStream_t stream);
+
+void smooth_channel(
+		ftl::cuda::TextureObject<uchar4> &colour_in,
+		//ftl::cuda::TextureObject<float> &depth_in,
+		ftl::cuda::TextureObject<float> &smoothing_out,
+		const ftl::rgbd::Camera &camera,
+		float alpha,
+		float scale,
+		int radius,
+		cudaStream_t stream);
+
+void depth_smooth(
+	ftl::cuda::TextureObject<float> &depth_in,
+	ftl::cuda::TextureObject<uchar4> &colour_in,
+	ftl::cuda::TextureObject<float> &depth_out,
+	const ftl::rgbd::Camera &camera,
+	int radius, float factor, float thresh, int iters,
+	cudaStream_t stream);
+
+void smoothing_factor(
+	ftl::cuda::TextureObject<float> &depth_in,
+	//ftl::cuda::TextureObject<float> &depth_tmp,
+	ftl::cuda::TextureObject<float> &temp,
+	//ftl::cuda::TextureObject<uchar4> &colour_in,
+	ftl::cuda::TextureObject<float> &smoothing,
+	float thresh,
+	const ftl::rgbd::Camera &camera,
+	cudaStream_t stream);
+
+}
+}
+
+#endif  // _FTL_CUDA_SMOOTHING_HPP_
diff --git a/components/renderers/cpp/include/ftl/cuda/normals.hpp b/components/renderers/cpp/include/ftl/cuda/normals.hpp
index 227ab536208b51321131b1e3eb7de98775bed971..dc3d0265ce4c142861bb0ca0b2e841dc81887449 100644
--- a/components/renderers/cpp/include/ftl/cuda/normals.hpp
+++ b/components/renderers/cpp/include/ftl/cuda/normals.hpp
@@ -24,6 +24,14 @@ void normals(ftl::cuda::TextureObject<float4> &output,
         const ftl::rgbd::Camera &camera,
         const float3x3 &pose_inv, const float3x3 &pose, cudaStream_t stream);
 
+void normals(ftl::cuda::TextureObject<float4> &output,
+        ftl::cuda::TextureObject<float4> &temp,
+        ftl::cuda::TextureObject<float> &input,
+		int radius,
+		float smoothing,
+        const ftl::rgbd::Camera &camera,
+        const float3x3 &pose_inv, const float3x3 &pose, cudaStream_t stream);
+
 void normals(ftl::cuda::TextureObject<float4> &output,
         ftl::cuda::TextureObject<float> &input,  // Integer depth values
         const ftl::rgbd::Camera &camera,
diff --git a/components/renderers/cpp/include/ftl/cuda/weighting.hpp b/components/renderers/cpp/include/ftl/cuda/weighting.hpp
index 15d3dbcec387f97d8ffe60690bdb5c1fda2c098c..bffff673d2009ac698c3c604ec565a2aa1a89901 100644
--- a/components/renderers/cpp/include/ftl/cuda/weighting.hpp
+++ b/components/renderers/cpp/include/ftl/cuda/weighting.hpp
@@ -25,6 +25,11 @@ __device__ inline float spatialWeighting(const float3 &a, const float3 &b, float
 	return rh*rh*rh*rh;
 }
 
+__device__ inline float colourDistance(uchar4 a, uchar4 b) {
+	const float3 delta = make_float3((float)a.x - (float)b.x, (float)a.y - (float)b.y, (float)a.z - (float)b.z);
+	return length(delta);
+}
+
 /*
  * Colour weighting as suggested in:
  * C. Kuster et al. Spatio-Temporal Geometry Fusion for Multiple Hybrid Cameras using Moving Least Squares Surfaces. 2014.
diff --git a/components/renderers/cpp/include/ftl/render/tri_render.hpp b/components/renderers/cpp/include/ftl/render/tri_render.hpp
index 57dc68a7b525ef423150f668cc3c6d8dfe8ea6ac..60d3dcbf6a68576981c1d72194dae731e8592fec 100644
--- a/components/renderers/cpp/include/ftl/render/tri_render.hpp
+++ b/components/renderers/cpp/include/ftl/render/tri_render.hpp
@@ -5,6 +5,7 @@
 #include <ftl/rgbd/frameset.hpp>
 #include <ftl/render/splat_params.hpp>
 #include <ftl/cuda/points.hpp>
+//#include <ftl/filters/filter.hpp>
 
 namespace ftl {
 namespace render {
@@ -42,11 +43,13 @@ class Triangular : public ftl::render::Renderer {
 	cudaStream_t stream_;
 	float3 light_pos_;
 
+	//ftl::Filters *filters_;
+
 	template <typename T>
 	void __reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t);
 	void _reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t);
-	void _dibr(cudaStream_t);
-	void _mesh(cudaStream_t);
+	void _dibr(ftl::rgbd::Frame &, cudaStream_t);
+	void _mesh(ftl::rgbd::Frame &, ftl::rgbd::Source *, cudaStream_t);
 };
 
 }
diff --git a/components/renderers/cpp/src/normals.cu b/components/renderers/cpp/src/normals.cu
index 7dcdf2f5fc705f78538cd799a196c1630f9dfc42..97452555dfb61fd5015aa6a1745b39e2ddcca409 100644
--- a/components/renderers/cpp/src/normals.cu
+++ b/components/renderers/cpp/src/normals.cu
@@ -208,6 +208,51 @@ __global__ void smooth_normals_kernel<0>(ftl::cuda::TextureObject<float4> norms,
     output(x,y) = n;
 }
 
+template <int RADIUS>
+__global__ void smooth_normals_kernel(ftl::cuda::TextureObject<float4> norms,
+        ftl::cuda::TextureObject<float4> output,
+        ftl::cuda::TextureObject<float> depth,
+        ftl::rgbd::Camera camera, float3x3 pose, float smoothing) {
+    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()) return;
+
+    const float3 p0 = camera.screenToCam(x,y, depth.tex2D((int)x,(int)y));
+    float3 nsum = make_float3(0.0f);
+    float contrib = 0.0f;
+
+    output(x,y) = make_float4(0.0f,0.0f,0.0f,0.0f);
+
+    if (p0.z < camera.minDepth || p0.z > camera.maxDepth) return;
+
+    for (int v=-RADIUS; v<=RADIUS; ++v) {
+        for (int u=-RADIUS; u<=RADIUS; ++u) {
+            const float3 p = camera.screenToCam(x+u,y+v, depth.tex2D((int)x+u,(int)y+v));
+            if (p.z < camera.minDepth || p.z > camera.maxDepth) continue;
+            const float s = ftl::cuda::spatialWeighting(p0, p, smoothing);
+            //const float s = 1.0f;
+
+            //if (s > 0.0f) {
+                const float4 n = norms.tex2D((int)x+u,(int)y+v);
+                if (n.w > 0.0f) {
+                    nsum += make_float3(n) * s;
+                    contrib += s;
+                }
+            //}
+        }
+    }
+
+    // Compute dot product of normal with camera to obtain measure of how
+    // well this point faces the source camera, a measure of confidence
+    float3 ray = camera.screenToCam(x, y, 1.0f);
+    ray = ray / length(ray);
+    nsum /= contrib;
+    nsum /= length(nsum);
+
+    output(x,y) = (contrib > 0.0f) ? make_float4(pose*nsum, 1.0f) : make_float4(0.0f);
+}
+
 void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
         ftl::cuda::TextureObject<float4> &temp,
 		ftl::cuda::TextureObject<float4> &input,
@@ -266,6 +311,34 @@ void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
 	#endif
 }
 
+void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
+		ftl::cuda::TextureObject<float4> &temp,
+		ftl::cuda::TextureObject<float> &input,
+		int radius,
+		float smoothing,
+		const ftl::rgbd::Camera &camera,
+		const float3x3 &pose_inv, const float3x3 &pose,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_kernel<<<gridSize, blockSize, 0, stream>>>(temp, input, camera);
+	cudaSafeCall( cudaGetLastError() );
+
+	switch (radius) {
+	case 7: smooth_normals_kernel<7><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
+	case 5: smooth_normals_kernel<5><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
+	case 3: smooth_normals_kernel<3><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
+	case 2: smooth_normals_kernel<2><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
+	case 1: smooth_normals_kernel<1><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
+	}
+	cudaSafeCall( cudaGetLastError() );
+
+	#ifdef _DEBUG
+	cudaSafeCall(cudaDeviceSynchronize());
+	//cutilCheckMsg(__FUNCTION__);
+	#endif
+}
+
 void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
         ftl::cuda::TextureObject<float> &input,
         const ftl::rgbd::Camera &camera,
diff --git a/components/renderers/cpp/src/reprojection.cu b/components/renderers/cpp/src/reprojection.cu
index c11d23dd137972f51628dd844a76b20e3a25993a..e74b4bb60963ab7d7d1798a96b22c90916a7ffc3 100644
--- a/components/renderers/cpp/src/reprojection.cu
+++ b/components/renderers/cpp/src/reprojection.cu
@@ -61,7 +61,7 @@ __device__ inline void accumulateOutput(TextureObject<float4> &out, TextureObjec
 __global__ void reprojection_kernel(
         TextureObject<A> in,				// Attribute input
         TextureObject<float> depth_src,
-		TextureObject<int> depth_in,        // Virtual depth map
+		TextureObject<float> depth_in,        // Virtual depth map
 		TextureObject<float4> normals,
 		TextureObject<B> out,			// Accumulated output
 		TextureObject<float> contrib,
@@ -71,7 +71,7 @@ __global__ void reprojection_kernel(
 	const int x = (blockIdx.x*blockDim.x + threadIdx.x);
 	const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
-	const float d = (float)depth_in.tex2D((int)x, (int)y) / 100000.0f;
+	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);
@@ -118,7 +118,7 @@ template <typename A, typename B>
 void ftl::cuda::reproject(
         TextureObject<A> &in,
         TextureObject<float> &depth_src,       // Original 3D points
-		TextureObject<int> &depth_in,        // Virtual depth map
+		TextureObject<float> &depth_in,        // Virtual depth map
 		TextureObject<float4> &normals,
 		TextureObject<B> &out,   // Accumulated output
 		TextureObject<float> &contrib,
@@ -144,7 +144,7 @@ void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 	ftl::cuda::TextureObject<uchar4> &in,	// Original colour image
 	ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-	ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+	ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 	ftl::cuda::TextureObject<float4> &normals,
 	ftl::cuda::TextureObject<float4> &out,	// Accumulated output
 	ftl::cuda::TextureObject<float> &contrib,
@@ -155,7 +155,7 @@ template void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 		ftl::cuda::TextureObject<float> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<float4> &normals,
 		ftl::cuda::TextureObject<float> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
@@ -166,7 +166,7 @@ template void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 		ftl::cuda::TextureObject<float4> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<float4> &normals,
 		ftl::cuda::TextureObject<float4> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
@@ -185,7 +185,7 @@ template void ftl::cuda::reproject(
 __global__ void reprojection_kernel(
         TextureObject<A> in,				// Attribute input
         TextureObject<float> depth_src,
-		TextureObject<int> depth_in,        // Virtual depth map
+		TextureObject<float> depth_in,        // Virtual depth map
 		TextureObject<B> out,			// Accumulated output
 		TextureObject<float> contrib,
 		SplatParams params,
@@ -194,7 +194,7 @@ __global__ void reprojection_kernel(
 	const int x = (blockIdx.x*blockDim.x + threadIdx.x);
 	const int y = blockIdx.y*blockDim.y + threadIdx.y;
 
-	const float d = (float)depth_in.tex2D((int)x, (int)y) / 100000.0f;
+	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);
@@ -224,7 +224,7 @@ template <typename A, typename B>
 void ftl::cuda::reproject(
         TextureObject<A> &in,
         TextureObject<float> &depth_src,       // Original 3D points
-		TextureObject<int> &depth_in,        // Virtual depth map
+		TextureObject<float> &depth_in,        // Virtual depth map
 		TextureObject<B> &out,   // Accumulated output
 		TextureObject<float> &contrib,
 		const SplatParams &params,
@@ -248,7 +248,7 @@ void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 	ftl::cuda::TextureObject<uchar4> &in,	// Original colour image
 	ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-	ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+	ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 	ftl::cuda::TextureObject<float4> &out,	// Accumulated output
 	ftl::cuda::TextureObject<float> &contrib,
 	const ftl::render::SplatParams &params,
@@ -258,7 +258,7 @@ template void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 		ftl::cuda::TextureObject<float> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<float> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
 		const ftl::render::SplatParams &params,
@@ -268,7 +268,7 @@ template void ftl::cuda::reproject(
 template void ftl::cuda::reproject(
 		ftl::cuda::TextureObject<float4> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<float4> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
 		const ftl::render::SplatParams &params,
diff --git a/components/renderers/cpp/src/splatter_cuda.hpp b/components/renderers/cpp/src/splatter_cuda.hpp
index 038f5a3e5b76b23aab1cfb9b1a7878154321ff2c..838eda409761c7420a35944a45900ace0912f124 100644
--- a/components/renderers/cpp/src/splatter_cuda.hpp
+++ b/components/renderers/cpp/src/splatter_cuda.hpp
@@ -66,7 +66,7 @@ namespace cuda {
 	void reproject(
 		ftl::cuda::TextureObject<A> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<float4> &normals,
 		ftl::cuda::TextureObject<B> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
@@ -78,7 +78,7 @@ namespace cuda {
 	void reproject(
 		ftl::cuda::TextureObject<A> &in,	// Original colour image
 		ftl::cuda::TextureObject<float> &depth_src,		// Original 3D points
-		ftl::cuda::TextureObject<int> &depth_in,		// Virtual depth map
+		ftl::cuda::TextureObject<float> &depth_in,		// Virtual depth map
 		ftl::cuda::TextureObject<B> &out,	// Accumulated output
 		ftl::cuda::TextureObject<float> &contrib,
 		const ftl::render::SplatParams &params,
diff --git a/components/renderers/cpp/src/tri_render.cpp b/components/renderers/cpp/src/tri_render.cpp
index 7f93a8f683507d6c5c393bb4b9bfbeedf5cab756..6d60a5f6685ac7d292d4a67b0d23df8b231f3b21 100644
--- a/components/renderers/cpp/src/tri_render.cpp
+++ b/components/renderers/cpp/src/tri_render.cpp
@@ -7,6 +7,8 @@
 
 #include <opencv2/core/cuda_stream_accessor.hpp>
 
+//#include <ftl/filters/smoothing.hpp>
+
 #include <string>
 
 using ftl::render::Triangular;
@@ -129,6 +131,9 @@ Triangular::Triangular(nlohmann::json &config, ftl::rgbd::FrameSet *fs) : ftl::r
 	on("light_z", [this](const ftl::config::Event &e) { light_pos_.z = value("light_z", 0.3f); });
 
 	cudaSafeCall(cudaStreamCreate(&stream_));
+
+	//filters_ = ftl::create<ftl::Filters>(this, "filters");
+	//filters_->create<ftl::filters::DepthSmoother>("hfnoise");
 }
 
 Triangular::~Triangular() {
@@ -215,9 +220,9 @@ void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann
 		if (mesh_) {
 			ftl::cuda::reproject(
 				f.createTexture<T>(in),
-				f.createTexture<float>(Channel::Depth),  // TODO: Use depth?
-				temp_.getTexture<int>(Channel::Depth2),
-				accum_.getTexture<float4>(Channel::Normals),
+				f.createTexture<float>(Channel::Depth),
+				output.getTexture<float>(Channel::Depth),
+				output.getTexture<float4>(Channel::Normals),
 				temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
 				temp_.getTexture<float>(Channel::Contribution),
 				params_,
@@ -228,8 +233,8 @@ void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann
 			// Can't use normals with point cloud version
 			ftl::cuda::reproject(
 				f.createTexture<T>(in),
-				f.createTexture<float>(Channel::Depth),  // TODO: Use depth?
-				temp_.getTexture<int>(Channel::Depth2),
+				f.createTexture<float>(Channel::Depth),
+				output.getTexture<float>(Channel::Depth),
 				temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
 				temp_.getTexture<float>(Channel::Contribution),
 				params_,
@@ -269,7 +274,7 @@ void Triangular::_reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Channe
 	}
 }
 
-void Triangular::_dibr(cudaStream_t stream) {
+void Triangular::_dibr(ftl::rgbd::Frame &out, cudaStream_t stream) {
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 	temp_.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0x7FFFFFFF), cvstream);
 
@@ -288,9 +293,12 @@ void Triangular::_dibr(cudaStream_t stream) {
 			params_, stream
 		);
 	}
+
+	// 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);
 }
 
-void Triangular::_mesh(cudaStream_t stream) {
+void Triangular::_mesh(ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) {
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
 
 	bool do_blend = value("mesh_blend", true);
@@ -346,6 +354,18 @@ void Triangular::_mesh(cudaStream_t stream) {
 			);
 		}
 	}
+
+	// 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);
+
+	//filters_->filter(out, src, stream);
+
+	// Generate normals for final virtual image
+	ftl::cuda::normals(out.createTexture<float4>(Channel::Normals, Format<float4>(params_.camera.width, params_.camera.height)),
+				temp_.createTexture<float4>(Channel::Normals),
+				out.createTexture<float>(Channel::Depth),
+				value("normal_radius", 1), value("normal_smoothing", 0.02f),
+				params_.camera, params_.m_viewMatrix.getFloat3x3(), params_.m_viewMatrixInverse.getFloat3x3(), stream_);
 }
 
 void Triangular::_renderChannel(
@@ -500,17 +520,10 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 
 	// Create and render triangles for depth
 	if (mesh_) {
-		_mesh(stream_);
+		_mesh(out, src, stream_);
 	} else {
-		_dibr(stream_);
+		_dibr(out, stream_);
 	}
-	
-	// Generate normals for final virtual image
-	ftl::cuda::normals(accum_.createTexture<float4>(Channel::Normals, Format<float4>(camera.width, camera.height)),
-				temp_.createTexture<float4>(Channel::Normals),
-				temp_.getTexture<int>(Channel::Depth2),
-				value("normal_radius", 1), value("normal_smoothing", 0.02f),
-				params_.camera, params_.m_viewMatrix.getFloat3x3(), params_.m_viewMatrixInverse.getFloat3x3(), stream_);
 
 	// Reprojection of colours onto surface
 	_renderChannel(out, Channel::Colour, Channel::Colour, stream_);
@@ -518,14 +531,16 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 	if (chan == Channel::Depth)
 	{
 		// Just convert 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>(Channel::Depth), CV_32F, 1.0f / 100000.0f, cvstream);
 	} else if (chan == Channel::Normals) {
 		// Visualise normals to RGBA
-		out.create<GpuMat>(Channel::Normals, Format<uchar4>(camera.width, camera.height)).setTo(cv::Scalar(0,0,0,0), cvstream);
-		ftl::cuda::normal_visualise(accum_.getTexture<float4>(Channel::Normals), out.createTexture<uchar4>(Channel::Normals),
+		accum_.create<GpuMat>(Channel::Normals, Format<uchar4>(camera.width, camera.height)).setTo(cv::Scalar(0,0,0,0), cvstream);
+		ftl::cuda::normal_visualise(out.getTexture<float4>(Channel::Normals), accum_.createTexture<uchar4>(Channel::Normals),
 				light_pos_,
 				light_diffuse_,
 				light_ambient_, stream_);
+
+		accum_.swapTo(Channels(Channel::Normals), out);
 	}
 	//else if (chan == Channel::Contribution)
 	//{
@@ -558,9 +573,9 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 
 		// Need to re-dibr due to pose change
 		if (mesh_) {
-			_mesh(stream_);
+			_mesh(out, src, stream_);
 		} else {
-			_dibr(stream_);
+			_dibr(out, stream_);
 		}
 		_renderChannel(out, Channel::Left, Channel::Right, stream_);
 
diff --git a/components/rgbd-sources/include/ftl/rgbd/camera.hpp b/components/rgbd-sources/include/ftl/rgbd/camera.hpp
index 9fd6b98a026d9e3edf2ccd09d1a2a3011cbb71bb..2d36b2f7565620efe9962297dddf2a0e3a45393e 100644
--- a/components/rgbd-sources/include/ftl/rgbd/camera.hpp
+++ b/components/rgbd-sources/include/ftl/rgbd/camera.hpp
@@ -29,6 +29,8 @@ struct __align__(16) Camera {
 	double baseline;		// For stereo pair
 	double doffs;			// Disparity offset
 
+	Camera scaled(int width, int height) const;
+
 	/**
 	 * Convert camera coordinates into screen coordinates.
 	 */
diff --git a/components/rgbd-sources/src/source.cpp b/components/rgbd-sources/src/source.cpp
index a7b6b2cb0e3081efa8371479a216d6dc21dce801..b0ee77a449e33b82641c18aa0c7a039ed42e8626 100644
--- a/components/rgbd-sources/src/source.cpp
+++ b/components/rgbd-sources/src/source.cpp
@@ -280,11 +280,12 @@ void Source::notifyRaw(const ftl::codecs::StreamPacket &spkt, const ftl::codecs:
 /*
  * Scale camera parameters to match resolution.
  */
-static Camera scaled(Camera &cam, int width, int height) {
+Camera Camera::scaled(int width, int height) const {
+	const auto &cam = *this;
 	float scaleX = (float)width / (float)cam.width;
 	float scaleY = (float)height / (float)cam.height;
 
-	CHECK( abs(scaleX - scaleY) < 0.000001f );
+	CHECK( abs(scaleX - scaleY) < 0.00000001f );
 
 	Camera newcam = cam;
 	newcam.width = width;
@@ -304,7 +305,7 @@ void Source::notify(int64_t ts, cv::cuda::GpuMat &c1, cv::cuda::GpuMat &c2) {
 
 	// Do we need to scale camera parameters
 	if (impl_->params_.width < max_width || impl_->params_.height < max_height) {
-		impl_->params_ = scaled(impl_->params_, max_width, max_height);
+		impl_->params_ = impl_->params_.scaled(max_width, max_height);
 	}
 
 	// Should channel 1 be scaled?