diff --git a/applications/ftl2mkv/src/main.cpp b/applications/ftl2mkv/src/main.cpp
index a6a7a2448869168e7634ecd40ba724ca964bdda5..598e372ca524d33e358c1f312fdeba5429fa0ea8 100644
--- a/applications/ftl2mkv/src/main.cpp
+++ b/applications/ftl2mkv/src/main.cpp
@@ -81,7 +81,7 @@ int main(int argc, char **argv) {
 		LOG(ERROR) << "Missing input ftl file.";
 		return -1;
 	} else {
-		filename = paths[0];
+		filename = paths[paths.size()-1];
 	}
 
 	std::ifstream f;
diff --git a/applications/reconstruct/CMakeLists.txt b/applications/reconstruct/CMakeLists.txt
index b089d4a1aeae9654b50865c7400ca0e381f874e6..5dc0ef5dbce517fb88cdf0fb0cc9fdc7b84a778a 100644
--- a/applications/reconstruct/CMakeLists.txt
+++ b/applications/reconstruct/CMakeLists.txt
@@ -20,6 +20,7 @@ set(REPSRC
 	src/ilw/fill.cu
 	src/ilw/discontinuity.cu
 	src/ilw/correspondence.cu
+	src/reconstruction.cpp
 )
 
 add_executable(ftl-reconstruct ${REPSRC})
diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp
index f3a92c93340de67bbee302a89dae93f01b550bcd..c4905e1e5c9713d8c89f7d926548c439797bc627 100644
--- a/applications/reconstruct/src/main.cpp
+++ b/applications/reconstruct/src/main.cpp
@@ -18,6 +18,8 @@
 #include <ftl/codecs/writer.hpp>
 #include <ftl/codecs/reader.hpp>
 
+#include "reconstruction.hpp"
+
 #include "ilw/ilw.hpp"
 #include <ftl/render/tri_render.hpp>
 
@@ -136,7 +138,16 @@ static void run(ftl::Configurable *root) {
 	net->start();
 	net->waitConnections();
 	
-	// Check paths for an FTL file to load...
+	std::vector<int> sourcecounts;
+
+	// Add sources from the configuration file as a single group.
+	auto configuration_sources = root->getConfig()["sources"];
+	size_t configuration_size = configuration_sources.size();
+	if (configuration_size > 0) {
+		sourcecounts.push_back(configuration_size);
+	}
+
+	// Check paths for FTL files to load.
 	auto paths = (*root->get<nlohmann::json>("paths"));
 	for (auto &x : paths.items()) {
 		std::string path = x.value().get<std::string>();
@@ -162,12 +173,14 @@ static void run(ftl::Configurable *root) {
 			int N = root->value("N", 100);
 
 			// For each stream found, add a source object
-			for (int i=0; i<=min(max_stream,N-1); ++i) {
+			int count = min(max_stream+1, N);
+			for (int i=0; i<count; ++i) {
 				root->getConfig()["sources"].push_back(nlohmann::json{{"uri",std::string("file://") + path + std::string("#") + std::to_string(i)}});
 			}
+			sourcecounts.push_back(count);
 		}
 	}
-	
+
 	// Create a vector of all input RGB-Depth sources
 	auto sources = ftl::createArray<Source>(root, "sources", net);
 
@@ -175,7 +188,7 @@ static void run(ftl::Configurable *root) {
 		LOG(ERROR) << "No sources configured!";
 		return;
 	}
-	
+
 	ConfigProxy *configproxy = nullptr;
 	if (net->numberOfPeers() > 0) {
 		configproxy = new ConfigProxy(net); // TODO delete
@@ -235,61 +248,57 @@ static void run(ftl::Configurable *root) {
 		}
 	}
 
-	ftl::rgbd::FrameSet scene_A;  // Output of align process
-	ftl::rgbd::FrameSet scene_B;  // Input of render process
+	ftl::rgbd::FrameSet fs_out;
 
 	//ftl::voxhash::SceneRep *scene = ftl::create<ftl::voxhash::SceneRep>(root, "voxelhash");
 	ftl::rgbd::Streamer *stream = ftl::create<ftl::rgbd::Streamer>(root, "stream", net);
-	ftl::rgbd::VirtualSource *virt = ftl::create<ftl::rgbd::VirtualSource>(root, "virtual");
+	ftl::rgbd::VirtualSource *vs = ftl::create<ftl::rgbd::VirtualSource>(root, "virtual");
 	//root->set("tags", nlohmann::json::array({ root->getID()+"/virtual" }));
-	ftl::render::Triangular *splat = ftl::create<ftl::render::Triangular>(root, "renderer", &scene_B);
-	ftl::rgbd::Group *group = new ftl::rgbd::Group;
-	ftl::ILW *align = ftl::create<ftl::ILW>(root, "merge");
 
 	int o = root->value("origin_pose", 0) % sources.size();
-	virt->setPose(sources[o]->getPose());
+	vs->setPose(sources[o]->getPose());
+
+	vector<ftl::Reconstruction*> groups;
+
+	size_t cumulative = 0;
+	for (auto c : sourcecounts) {
+		std::string id = std::to_string(cumulative);
+		auto reconstr = ftl::create<ftl::Reconstruction>(root, id, id);
+		for (size_t i=cumulative; i<cumulative+c; i++) {
+			reconstr->addSource(sources[i]);
+		}
+		groups.push_back(reconstr);
+		cumulative += c;
+	}
 
 	auto *renderpipe = ftl::config::create<ftl::operators::Graph>(root, "render_pipe");
 	renderpipe->append<ftl::operators::ColourChannels>("colour");  // Generate interpolation texture...
 	renderpipe->append<ftl::operators::FXAA>("antialiasing"); 
 
-	// Generate virtual camera render when requested by streamer
-	virt->onRender([splat,virt,&scene_B,align,renderpipe](ftl::rgbd::Frame &out) {
-		//virt->setTimestamp(scene_B.timestamp);
-		// Do we need to convert Lab to BGR?
-		if (align->isLabColour()) {
-			for (auto &f : scene_B.frames) {
-				auto &col = f.get<cv::cuda::GpuMat>(Channel::Colour);
-				cv::cuda::cvtColor(col,col, cv::COLOR_Lab2BGR); // TODO: Add stream
-			}
+	vs->onRender([vs, &groups, &renderpipe](ftl::rgbd::Frame &out) {
+		for (auto &reconstr : groups) {
+			reconstr->render(vs, out);
 		}
-		splat->render(virt, out);
-		renderpipe->apply(out, out, virt, 0);
+		renderpipe->apply(out, out, vs, 0);
 	});
-	stream->add(virt);
-
-	for (size_t i=0; i<sources.size(); i++) {
-		Source *in = sources[i];
-		in->setChannel(Channel::Depth);
-		group->addSource(in);
-	}
+	stream->add(vs);
 
 	// ---- Recording code -----------------------------------------------------
-
+	/*
 	std::ofstream fileout;
 	ftl::codecs::Writer writer(fileout);
-	auto recorder = [&writer,&group](ftl::rgbd::Source *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) {
+	auto recorder = [&writer,&groups](ftl::rgbd::Source *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) {
 		ftl::codecs::StreamPacket s = spkt;
 
 		// Patch stream ID to match order in group
-		s.streamID = group->streamID(src);
+		s.streamID = groups[0]->streamID(src);
 		writer.write(s, pkt);
 	};
 
 	root->set("record", false);
 
 	// Allow stream recording
-	root->on("record", [&group,&fileout,&writer,&recorder](const ftl::config::Event &e) {
+	root->on("record", [&groups,&fileout,&writer,&recorder](const ftl::config::Event &e) {
 		if (e.entity->value("record", false)) {
 			char timestamp[18];
 			std::time_t t=std::time(NULL);
@@ -297,85 +306,30 @@ static void run(ftl::Configurable *root) {
 			fileout.open(std::string(timestamp) + ".ftl");
 
 			writer.begin();
-			group->addRawCallback(std::function(recorder));
+			// TODO: Add to all grounds / reconstructions
+			groups[0]->addRawCallback(std::function(recorder));
 
 			// TODO: Write pose+calibration+config packets
-			auto sources = group->sources();
+			auto sources = groups[0]->sources();
 			for (size_t i=0; i<sources.size(); ++i) {
 				//writeSourceProperties(writer, i, sources[i]);
 				sources[i]->inject(Channel::Calibration, sources[i]->parameters(), Channel::Left, sources[i]->getCapabilities());
 				sources[i]->inject(sources[i]->getPose()); 
 			}
 		} else {
-			group->removeRawCallback(recorder);
+			// FIXME: Remove doesn't work, so multiple records fail.
+			groups[0]->removeRawCallback(recorder);
 			writer.end();
 			fileout.close();
 		}
 	});
-
+	*/
 	// -------------------------------------------------------------------------
 
 	stream->setLatency(6);  // FIXME: This depends on source!?
 	//stream->add(group);
 	stream->run();
 
-	bool busy = false;
-
-	// Create the source depth map pipeline
-	auto *pipeline1 = ftl::config::create<ftl::operators::Graph>(root, "pre_filters");
-	pipeline1->append<ftl::operators::ClipScene>("clipping");
-	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::ScanFieldFill>("filling");  // Generate a smoothing channel
-	pipeline1->append<ftl::operators::CrossSupport>("cross");
-	pipeline1->append<ftl::operators::DiscontinuityMask>("discontinuity");
-	pipeline1->append<ftl::operators::CrossSupport>("cross2")->set("discon_support", true);
-	pipeline1->append<ftl::operators::CullDiscontinuity>("remove_discontinuity");
-	//pipeline1->append<ftl::operators::AggreMLS>("mls");  // Perform MLS (using smoothing channel)
-	pipeline1->append<ftl::operators::VisCrossSupport>("viscross")->set("enabled", false);
-	pipeline1->append<ftl::operators::MultiViewMLS>("mvmls");
-	// Alignment
-
-
-	group->setLatency(4);
-	group->setName("ReconGroup");
-	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;
-		if (controls->value("paused", false)) return true;
-		
-		if (busy) {
-			LOG(INFO) << "Group frameset dropped: " << fs.timestamp;
-			return true;
-		}
-		busy = true;
-
-		// Swap the entire frameset to allow rapid return
-		fs.swapTo(scene_A);
-
-		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);
-
-			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);
-			LOG(INFO) << "Align complete... " << scene_A.timestamp;
-			busy = false;
-		});
-		return true;
-	});
-
 	LOG(INFO) << "Start timer";
 	ftl::timer::start(true);
 
@@ -389,12 +343,12 @@ static void run(ftl::Configurable *root) {
 
 	LOG(INFO) << "Deleting...";
 
-	delete align;
-	delete splat;
 	delete stream;
-	delete virt;
+	delete vs;
 	delete net;
-	delete group;
+	for (auto g : groups) {
+		delete g;
+	}
 
 	ftl::config::cleanup();  // Remove any last configurable objects.
 	LOG(INFO) << "Done.";
diff --git a/applications/reconstruct/src/reconstruction.cpp b/applications/reconstruct/src/reconstruction.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..bbaf7f8b5e6414140233aa9480ccc1239c7de262
--- /dev/null
+++ b/applications/reconstruct/src/reconstruction.cpp
@@ -0,0 +1,77 @@
+#include "reconstruction.hpp"
+
+#include "ftl/operators/smoothing.hpp"
+#include "ftl/operators/colours.hpp"
+#include "ftl/operators/normals.hpp"
+#include "ftl/operators/filling.hpp"
+#include "ftl/operators/segmentation.hpp"
+#include "ftl/operators/mask.hpp"
+#include "ftl/operators/antialiasing.hpp"
+#include "ftl/operators/mvmls.hpp"
+#include "ftl/operators/clipping.hpp"
+
+using ftl::Reconstruction;
+using ftl::codecs::Channel;
+
+Reconstruction::Reconstruction(nlohmann::json &config, const std::string name) :
+	ftl::Configurable(config), busy_(false), fs_render_(), fs_align_() {
+	group_ = new ftl::rgbd::Group;
+	group_->setName("ReconGroup-" + name);
+	group_->setLatency(4);
+
+	renderer_ = ftl::create<ftl::render::Triangular>(this, "renderer", &fs_render_);
+
+	pipeline_ = ftl::config::create<ftl::operators::Graph>(this, "pre_filters");
+	pipeline_->append<ftl::operators::ClipScene>("clipping")->set("enabled", false);
+	pipeline_->append<ftl::operators::ColourChannels>("colour");  // Convert BGR to BGRA
+	//pipeline_->append<ftl::operators::HFSmoother>("hfnoise");  // Remove high-frequency noise
+	pipeline_->append<ftl::operators::Normals>("normals");  // Estimate surface normals
+	//pipeline_->append<ftl::operators::SmoothChannel>("smoothing");  // Generate a smoothing channel
+	//pipeline_->append<ftl::operators::ScanFieldFill>("filling");  // Generate a smoothing channel
+	pipeline_->append<ftl::operators::CrossSupport>("cross");
+	pipeline_->append<ftl::operators::DiscontinuityMask>("discontinuity");
+	pipeline_->append<ftl::operators::CrossSupport>("cross2")->set("discon_support", true);
+	pipeline_->append<ftl::operators::CullDiscontinuity>("remove_discontinuity");
+	//pipeline_->append<ftl::operators::AggreMLS>("mls");  // Perform MLS (using smoothing channel)
+	pipeline_->append<ftl::operators::VisCrossSupport>("viscross")->set("enabled", false);
+	pipeline_->append<ftl::operators::MultiViewMLS>("mvmls");
+
+	group_->sync([this](ftl::rgbd::FrameSet &fs) -> bool {
+		// TODO: pause
+		
+		if (busy_) {
+			LOG(INFO) << "Group frameset dropped: " << fs.timestamp;
+			return true;
+		}
+		busy_ = true;
+
+		// Swap the entire frameset to allow rapid return
+		fs.swapTo(fs_align_);
+
+		ftl::pool.push([this](int id) {
+			UNIQUE_LOCK(fs_align_.mtx, lk);
+			pipeline_->apply(fs_align_, fs_align_, 0);
+			
+			// TODO: To use second GPU, could do a download, swap, device change,
+			// then upload to other device. Or some direct device-2-device copy.
+			fs_align_.swapTo(fs_render_);
+
+			LOG(INFO) << "Align complete... " << fs_align_.timestamp;
+			busy_ = false;
+		});
+		return true;
+	});
+}
+
+Reconstruction::~Reconstruction() {
+	// TODO delete
+}
+
+void Reconstruction::addSource(ftl::rgbd::Source *src) {
+	src->setChannel(Channel::Depth);
+	group_->addSource(src); // TODO: check if source is already in group?
+}
+
+void Reconstruction::render(ftl::rgbd::VirtualSource *vs, ftl::rgbd::Frame &out) {
+	renderer_->render(vs, out);
+}
\ No newline at end of file
diff --git a/applications/reconstruct/src/reconstruction.hpp b/applications/reconstruct/src/reconstruction.hpp
new file mode 100644
index 0000000000000000000000000000000000000000..340e65bf2f47650400d4c6850c1ae1310a0458aa
--- /dev/null
+++ b/applications/reconstruct/src/reconstruction.hpp
@@ -0,0 +1,37 @@
+#ifndef _FTL_RECONSTRUCTION_HPP_
+#define _FTL_RECONSTRUCTION_HPP_
+
+#include "ftl/configurable.hpp"
+#include "ftl/rgbd/source.hpp"
+#include "ftl/rgbd/frame.hpp"
+#include "ftl/rgbd/group.hpp"
+#include "ftl/rgbd/frameset.hpp"
+#include "ftl/operators/operator.hpp"
+#include "ftl/render/tri_render.hpp"
+
+namespace ftl {
+
+class Reconstruction : public ftl::Configurable {
+	public:
+	Reconstruction(nlohmann::json &config, const std::string name);
+	~Reconstruction();
+
+	void addSource(ftl::rgbd::Source *);
+
+	/**
+	 * Do the render for a specified virtual camera.
+	 */
+	void render(ftl::rgbd::VirtualSource *vs, ftl::rgbd::Frame &out);
+
+	private:
+	bool busy_;
+	ftl::rgbd::FrameSet fs_render_;
+	ftl::rgbd::FrameSet fs_align_;
+	ftl::rgbd::Group *group_;
+	ftl::operators::Graph *pipeline_;
+	ftl::render::Triangular *renderer_;
+};
+
+}
+
+#endif  // _FTL_RECONSTRUCTION_HPP_
diff --git a/components/common/cpp/src/configuration.cpp b/components/common/cpp/src/configuration.cpp
index efeea93e6789c8b30fca1f1a67838e26e08546ac..f8c982a811652252f14205b00e7f778d906ab8ed 100644
--- a/components/common/cpp/src/configuration.cpp
+++ b/components/common/cpp/src/configuration.cpp
@@ -581,12 +581,12 @@ Configurable *ftl::config::configure(int argc, char **argv, const std::string &r
 	// Process Arguments
 	auto options = ftl::config::read_options(&argv, &argc);
 	
-	vector<string> paths;
+	vector<string> paths(argc);
 	while (argc-- > 0) {
 		paths.push_back(argv[0]);
 		argv++;
 	}
-	
+
 	if (!findConfiguration(options["config"], paths)) {
 		LOG(FATAL) << "Could not find any configuration!";
 	}
diff --git a/components/renderers/cpp/src/splatter_cuda.hpp b/components/renderers/cpp/src/splatter_cuda.hpp
index c81977cf38a4380df4143d2cd8d0609c69de8897..53b9f675e9f26144e9f2d31fff9c889b3ef58720 100644
--- a/components/renderers/cpp/src/splatter_cuda.hpp
+++ b/components/renderers/cpp/src/splatter_cuda.hpp
@@ -117,6 +117,11 @@ namespace cuda {
         ftl::cuda::TextureObject<uchar4> &colour,
 		ftl::cuda::TextureObject<int> &mask,
         int id, uchar4 style, cudaStream_t stream);
+
+	void merge_convert_depth(
+        ftl::cuda::TextureObject<int> &d1,
+		ftl::cuda::TextureObject<float> &d2,
+        float factor, cudaStream_t stream);
 }
 }
 
diff --git a/components/renderers/cpp/src/tri_render.cpp b/components/renderers/cpp/src/tri_render.cpp
index 5d38742cf979575fd24388689b6cb5899821af65..05edcb2efab4aa2ea124ca167175c852864b2c86 100644
--- a/components/renderers/cpp/src/tri_render.cpp
+++ b/components/renderers/cpp/src/tri_render.cpp
@@ -374,7 +374,8 @@ void Triangular::_mesh(ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream
 	}
 
 	// Convert from int depth to float depth
-	temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(Channel::Depth), CV_32F, 1.0f / 100000.0f, cvstream);
+	//temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(Channel::Depth), CV_32F, 1.0f / 100000.0f, cvstream);
+	ftl::cuda::merge_convert_depth(temp_.getTexture<int>(Channel::Depth2), out.createTexture<float>(Channel::Depth), 1.0f / 100000.0f, stream_);
 
 	//filters_->filter(out, src, stream);
 
@@ -470,25 +471,8 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 	//scene_->upload(Channel::Colour + Channel::Depth, stream_);
 
 	const auto &camera = src->parameters();
-	//cudaSafeCall(cudaSetDevice(scene_->getCUDADevice()));
-
-	// Create all the required channels
-	
-	out.create<GpuMat>(Channel::Depth, Format<float>(camera.width, camera.height));
-	out.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height));
-	out.createTexture<uchar4>(Channel::Colour, true);  // Force interpolated colour
-
-
-	if (scene_->frames.size() == 0) return false;
-	auto &g = scene_->frames[0].get<GpuMat>(Channel::Colour);
-
-	temp_.create<GpuMat>(Channel::Colour, Format<float4>(camera.width, camera.height));
-	temp_.create<GpuMat>(Channel::Contribution, Format<float>(camera.width, camera.height));
-	temp_.create<GpuMat>(Channel::Depth, Format<int>(camera.width, camera.height));
-	temp_.create<GpuMat>(Channel::Depth2, Format<int>(camera.width, camera.height));
-	temp_.create<GpuMat>(Channel::Normals, Format<float4>(camera.width, camera.height)); //g.cols, g.rows));
-
 	cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
+	//cudaSafeCall(cudaSetDevice(scene_->getCUDADevice()));
 
 	// Parameters object to pass to CUDA describing the camera
 	SplatParams &params = params_;
@@ -500,20 +484,36 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
 	params.m_viewMatrix = MatrixConversion::toCUDA(src->getPose().cast<float>().inverse());
 	params.m_viewMatrixInverse = MatrixConversion::toCUDA(src->getPose().cast<float>());
 	params.camera = camera;
-	// Clear all channels to 0 or max depth
 
-	out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
+	// Create all the required channels
+	
+	if (!out.hasChannel(Channel::Depth)) {
+		out.create<GpuMat>(Channel::Depth, Format<float>(camera.width, camera.height));
+		out.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height));
+		out.createTexture<uchar4>(Channel::Colour, true);  // Force interpolated colour
 
-	if (env_image_.empty() || !value("environment_enabled", false)) {
-		out.get<GpuMat>(Channel::Colour).setTo(background_, cvstream);
-	} else {
-		auto pose = params.m_viewMatrixInverse.getFloat3x3();
-		ftl::cuda::equirectangular_reproject(
-			env_tex_,
-			out.createTexture<uchar4>(Channel::Colour, true),
-			camera, pose, stream_);
+		out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
+
+		if (env_image_.empty() || !value("environment_enabled", false)) {
+			out.get<GpuMat>(Channel::Colour).setTo(background_, cvstream);
+		} else {
+			auto pose = params.m_viewMatrixInverse.getFloat3x3();
+			ftl::cuda::equirectangular_reproject(
+				env_tex_,
+				out.createTexture<uchar4>(Channel::Colour, true),
+				camera, pose, stream_);
+		}
 	}
 
+	if (scene_->frames.size() == 0) return false;
+	auto &g = scene_->frames[0].get<GpuMat>(Channel::Colour);
+
+	temp_.create<GpuMat>(Channel::Colour, Format<float4>(camera.width, camera.height));
+	temp_.create<GpuMat>(Channel::Contribution, Format<float>(camera.width, camera.height));
+	temp_.create<GpuMat>(Channel::Depth, Format<int>(camera.width, camera.height));
+	temp_.create<GpuMat>(Channel::Depth2, Format<int>(camera.width, camera.height));
+	temp_.create<GpuMat>(Channel::Normals, Format<float4>(camera.width, camera.height)); //g.cols, g.rows));
+
 	//LOG(INFO) << "Render ready: " << camera.width << "," << camera.height;
 
 	bool show_discon = value("show_discontinuity_mask", false);
diff --git a/components/renderers/cpp/src/triangle_render.cu b/components/renderers/cpp/src/triangle_render.cu
index 7311e50b9bbbd7b7ba78f106e360998b937646d8..2e1966c4252fcf751639cc70a94dbfbdccd43b3b 100644
--- a/components/renderers/cpp/src/triangle_render.cu
+++ b/components/renderers/cpp/src/triangle_render.cu
@@ -165,6 +165,30 @@ void ftl::cuda::triangle_render1(TextureObject<float> &depth_in, TextureObject<i
     cudaSafeCall( cudaGetLastError() );
 }
 
+// ==== Merge convert ===========
+
+__global__ void merge_convert_kernel(
+		TextureObject<int> depth_in,
+		TextureObject<float> depth_out,
+		float alpha) {
+	const int x = blockIdx.x*blockDim.x + threadIdx.x;
+	const int y = blockIdx.y*blockDim.y + threadIdx.y;
+
+	if (x < 0 || x >= depth_in.width() || y < 0 || y >= depth_in.height()) return;
+
+	float a = float(depth_in.tex2D(x,y))*alpha;
+	float b = depth_out.tex2D(x,y);
+	depth_out(x,y) = min(a,b);
+}
+
+void ftl::cuda::merge_convert_depth(TextureObject<int> &depth_in, TextureObject<float> &depth_out, float alpha, cudaStream_t stream) {
+	const dim3 gridSize((depth_in.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth_in.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	merge_convert_kernel<<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, alpha);
+	cudaSafeCall( cudaGetLastError() );
+}
+
 // ==== BLENDER ========
 
 /*