From 997b99f908e9c99a0ce9a089ce11293ec075564f Mon Sep 17 00:00:00 2001
From: Nicolas Pope <nwpope@utu.fi>
Date: Thu, 14 May 2020 22:53:03 +0300
Subject: [PATCH] Fixes for full colour clipping

---
 .../reconstruct/src/reconstruction.cpp        | 12 ++++----
 components/operators/src/clipping.cpp         | 13 +++++++--
 .../renderers/cpp/include/ftl/cuda/points.hpp |  5 ++++
 components/renderers/cpp/src/clipping.cu      | 28 +++++++++++++++++++
 4 files changed, 49 insertions(+), 9 deletions(-)

diff --git a/applications/reconstruct/src/reconstruction.cpp b/applications/reconstruct/src/reconstruction.cpp
index 86a738bdc..c55f1f5f1 100644
--- a/applications/reconstruct/src/reconstruction.cpp
+++ b/applications/reconstruct/src/reconstruction.cpp
@@ -24,23 +24,23 @@ Reconstruction::Reconstruction(nlohmann::json &config, const std::string name) :
 
 	pipeline_ = ftl::config::create<ftl::operators::Graph>(this, "pre_filters");
 	pipeline_->append<ftl::operators::DepthChannel>("depth");  // Ensure there is a depth channel
-	pipeline_->append<ftl::operators::DisparityBilateralFilter>("bilateral_filter")->set("enabled", false);
-	pipeline_->append<ftl::operators::DisparityToDepth>("calculate_depth")->set("enabled", false);
-	pipeline_->append<ftl::operators::ClipScene>("clipping")->set("enabled", false);
+	pipeline_->append<ftl::operators::DisparityBilateralFilter>("bilateral_filter")->value("enabled", false);
+	pipeline_->append<ftl::operators::DisparityToDepth>("calculate_depth")->value("enabled", false);
+	pipeline_->append<ftl::operators::ColourChannels>("colour");  // Convert BGR to BGRA
+	pipeline_->append<ftl::operators::ClipScene>("clipping")->value("enabled", false);
 	pipeline_->append<ftl::operators::DetectAndTrack>("facedetection")->value("enabled", false);
 	pipeline_->append<ftl::operators::ArUco>("aruco")->value("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::CrossSupport>("cross2")->value("discon_support", true);
 	pipeline_->append<ftl::operators::BorderMask>("border_mask")->value("enabled", false);
 	pipeline_->append<ftl::operators::CullDiscontinuity>("remove_discontinuity")->set("enabled", false);
 	//pipeline_->append<ftl::operators::AggreMLS>("mls");  // Perform MLS (using smoothing channel)
-	pipeline_->append<ftl::operators::VisCrossSupport>("viscross")->set("enabled", false);
+	pipeline_->append<ftl::operators::VisCrossSupport>("viscross")->value("enabled", false);
 	pipeline_->append<ftl::operators::MultiViewMLS>("mvmls");
 	pipeline_->append<ftl::operators::Poser>("poser")->value("enabled", false);
 
diff --git a/components/operators/src/clipping.cpp b/components/operators/src/clipping.cpp
index 17529bed2..bb03df096 100644
--- a/components/operators/src/clipping.cpp
+++ b/components/operators/src/clipping.cpp
@@ -57,6 +57,7 @@ bool ClipScene::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStr
 	shape.type = ftl::codecs::Shape3DType::CLIPPING;
 
 	bool no_clip = config()->value("no_clip", false);
+	bool clip_colour = config()->value("clip_colour", false);
 
 	std::vector<ftl::codecs::Shape3D> shapes;
 	if (in.hasChannel(Channel::Shapes3D)) {
@@ -77,9 +78,15 @@ bool ClipScene::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStr
 			auto sclip = clip;
 			sclip.origin = sclip.origin.getInverse() * pose;
 			if (!no_clip) {
-				//f.create<cv::cuda::GpuMat>(Channel::Depth);  // Force reset.
-				f.clearPackets(Channel::Depth);
-				ftl::cuda::clipping(f.createTexture<float>(Channel::Depth), f.getLeftCamera(), sclip, stream);
+				if (clip_colour) {
+					f.clearPackets(Channel::Colour);
+					f.clearPackets(Channel::Depth);
+					LOG(INFO) << "Clipping colour";
+					ftl::cuda::clipping(f.createTexture<float>(Channel::Depth), f.getTexture<uchar4>(Channel::Colour), f.getLeftCamera(), sclip, stream);
+				} else {
+					f.clearPackets(Channel::Depth);
+					ftl::cuda::clipping(f.createTexture<float>(Channel::Depth), f.getLeftCamera(), sclip, stream);
+				}
 			}
 		}
 	}
diff --git a/components/renderers/cpp/include/ftl/cuda/points.hpp b/components/renderers/cpp/include/ftl/cuda/points.hpp
index 3b31a0be1..45dc08fea 100644
--- a/components/renderers/cpp/include/ftl/cuda/points.hpp
+++ b/components/renderers/cpp/include/ftl/cuda/points.hpp
@@ -25,6 +25,11 @@ void clipping(ftl::cuda::TextureObject<float> &depth,
 		const ftl::rgbd::Camera &camera,
 		const ClipSpace &clip, cudaStream_t stream);
 
+void clipping(ftl::cuda::TextureObject<float> &depth,
+		ftl::cuda::TextureObject<uchar4> &colour,
+		const ftl::rgbd::Camera &camera,
+		const ClipSpace &clip, cudaStream_t stream);
+
 void point_cloud(ftl::cuda::TextureObject<float> &output, ftl::cuda::TextureObject<float4> &points, const ftl::rgbd::Camera &params, const float4x4 &poseinv, cudaStream_t stream);
 
 void world_to_cam(ftl::cuda::TextureObject<float4> &points, const float4x4 &poseinv, cudaStream_t stream);
diff --git a/components/renderers/cpp/src/clipping.cu b/components/renderers/cpp/src/clipping.cu
index 0fae98e11..016e08855 100644
--- a/components/renderers/cpp/src/clipping.cu
+++ b/components/renderers/cpp/src/clipping.cu
@@ -22,6 +22,22 @@ __global__ void clipping_kernel(ftl::cuda::TextureObject<float> depth, ftl::rgbd
 	}
 }
 
+__global__ void clipping_kernel(ftl::cuda::TextureObject<float> depth, ftl::cuda::TextureObject<uchar4> colour, ftl::rgbd::Camera camera, ftl::cuda::ClipSpace clip)
+{
+	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()) {
+		float d = depth(x,y);
+		float4 p = make_float4(camera.screenToCam(x,y,d), 0.0f);
+
+		if (d <= camera.minDepth || d >= camera.maxDepth || isClipped(p, clip)) {
+			depth(x,y) = 0.0f;
+			colour(x,y) = make_uchar4(0,0,0,0);
+		}
+	}
+}
+
 void ftl::cuda::clipping(ftl::cuda::TextureObject<float> &depth,
 		const ftl::rgbd::Camera &camera,
 		const ClipSpace &clip, cudaStream_t stream) {
@@ -31,4 +47,16 @@ void ftl::cuda::clipping(ftl::cuda::TextureObject<float> &depth,
 
 	clipping_kernel<<<gridSize, blockSize, 0, stream>>>(depth, camera, clip);
 	cudaSafeCall( cudaGetLastError() );
+}
+
+void ftl::cuda::clipping(ftl::cuda::TextureObject<float> &depth,
+		ftl::cuda::TextureObject<uchar4> &colour,
+		const ftl::rgbd::Camera &camera,
+		const ClipSpace &clip, cudaStream_t stream) {
+
+	const dim3 gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
+	const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
+
+	clipping_kernel<<<gridSize, blockSize, 0, stream>>>(depth, colour, camera, clip);
+	cudaSafeCall( cudaGetLastError() );
 }
\ No newline at end of file
-- 
GitLab