diff --git a/applications/reconstruct/src/depth_camera.cpp b/applications/reconstruct/src/depth_camera.cpp deleted file mode 100644 index de310f592b303dbcf7d041087863bf6c76db9305..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/depth_camera.cpp +++ /dev/null @@ -1,55 +0,0 @@ -#include <loguru.hpp> -#include <ftl/depth_camera.hpp> -#include "depth_camera_cuda.hpp" -#include <opencv2/core/cuda_stream_accessor.hpp> - -using ftl::voxhash::DepthCamera; -using ftl::voxhash::DepthCameraCUDA; - -DepthCamera::DepthCamera() { - depth_tex_ = nullptr; - depth2_tex_ = nullptr; - points_tex_ = nullptr; - colour_tex_ = nullptr; - normal_tex_ = nullptr; -} - -void DepthCamera::alloc(const DepthCameraParams& params, bool withNormals) { //! todo resizing??? - depth_tex_ = new ftl::cuda::TextureObject<float>(params.m_imageWidth, params.m_imageHeight); - depth2_tex_ = new ftl::cuda::TextureObject<int>(params.m_imageWidth, params.m_imageHeight); - points_tex_ = new ftl::cuda::TextureObject<float4>(params.m_imageWidth, params.m_imageHeight); - colour_tex_ = new ftl::cuda::TextureObject<uchar4>(params.m_imageWidth, params.m_imageHeight); - data.depth = depth_tex_->cudaTexture(); - data.depth2 = depth2_tex_->cudaTexture(); - data.points = points_tex_->cudaTexture(); - data.colour = colour_tex_->cudaTexture(); - data.params = params; - - //if (withNormals) { - normal_tex_ = new ftl::cuda::TextureObject<float4>(params.m_imageWidth, params.m_imageHeight); - data.normal = normal_tex_->cudaTexture(); - //} else { - // data.normal = 0; - //} -} - -void DepthCamera::free() { - delete depth_tex_; - delete colour_tex_; - delete depth2_tex_; - delete points_tex_; - if (normal_tex_) delete normal_tex_; -} - -void DepthCamera::updateData(const cv::Mat &depth, const cv::Mat &rgb, cv::cuda::Stream &stream) { - depth_tex_->upload(depth, cv::cuda::StreamAccessor::getStream(stream)); - colour_tex_->upload(rgb, cv::cuda::StreamAccessor::getStream(stream)); - //if (normal_mat_) { - //computeNormals(cv::cuda::StreamAccessor::getStream(stream)); - //} -} - -void DepthCamera::computeNormals(cudaStream_t stream) { - //ftl::cuda::point_cloud(*points_tex_, data, stream); - ftl::cuda::compute_normals(*depth_tex_, *normal_tex_, data, stream); -} diff --git a/applications/reconstruct/src/depth_camera.cu b/applications/reconstruct/src/depth_camera.cu deleted file mode 100644 index 7a322eaf733230772e72c50722e849335bf7e891..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/depth_camera.cu +++ /dev/null @@ -1,355 +0,0 @@ -#include <ftl/cuda_common.hpp> -#include <ftl/cuda_util.hpp> -#include <ftl/depth_camera.hpp> -#include "depth_camera_cuda.hpp" - -#define T_PER_BLOCK 16 -#define MINF __int_as_float(0xff800000) - -using ftl::voxhash::DepthCameraCUDA; -using ftl::voxhash::HashData; -using ftl::voxhash::HashParams; -using ftl::cuda::TextureObject; -using ftl::render::SplatParams; - -extern __constant__ ftl::voxhash::DepthCameraCUDA c_cameras[MAX_CAMERAS]; -extern __constant__ HashParams c_hashParams; - -__global__ void clear_depth_kernel(ftl::cuda::TextureObject<float> depth) { - 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()) { - depth(x,y) = 1000.0f; //PINF; - //colour(x,y) = make_uchar4(76,76,82,0); - } -} - -void ftl::cuda::clear_depth(const ftl::cuda::TextureObject<float> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_depth_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -__global__ void clear_depth_kernel(ftl::cuda::TextureObject<int> depth) { - 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()) { - depth(x,y) = 0x7FFFFFFF; //PINF; - //colour(x,y) = make_uchar4(76,76,82,0); - } -} - -void ftl::cuda::clear_depth(const ftl::cuda::TextureObject<int> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_depth_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -__global__ void clear_to_zero_kernel(ftl::cuda::TextureObject<float> depth) { - 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()) { - depth(x,y) = 0.0f; //PINF; - } -} - -void ftl::cuda::clear_to_zero(const ftl::cuda::TextureObject<float> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_to_zero_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -__global__ void clear_points_kernel(ftl::cuda::TextureObject<float4> depth) { - 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()) { - depth(x,y) = make_float4(MINF,MINF,MINF,MINF); - //colour(x,y) = make_uchar4(76,76,82,0); - } -} - -void ftl::cuda::clear_points(const ftl::cuda::TextureObject<float4> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_points_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -__global__ void clear_colour_kernel(ftl::cuda::TextureObject<uchar4> depth) { - 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()) { - depth(x,y) = make_uchar4(76,76,76,76); - //colour(x,y) = make_uchar4(76,76,82,0); - } -} - -void ftl::cuda::clear_colour(const ftl::cuda::TextureObject<uchar4> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_colour_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -__global__ void clear_colour_kernel(ftl::cuda::TextureObject<float4> depth) { - 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()) { - depth(x,y) = make_float4(0.0f); - } -} - -void ftl::cuda::clear_colour(const ftl::cuda::TextureObject<float4> &depth, cudaStream_t stream) { - const dim3 clear_gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 clear_blockSize(T_PER_BLOCK, T_PER_BLOCK); - clear_colour_kernel<<<clear_gridSize, clear_blockSize, 0, stream>>>(depth); -} - -// ===== Type convert ===== - -template <typename A, typename B> -__global__ void convert_kernel(const ftl::cuda::TextureObject<A> in, ftl::cuda::TextureObject<B> out, float scale) { - const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; - const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; - - if (x < in.width() && y < in.height()) { - out(x,y) = ((float)in.tex2D((int)x,(int)y)) * scale; - } -} - -void ftl::cuda::float_to_int(const ftl::cuda::TextureObject<float> &in, ftl::cuda::TextureObject<int> &out, float scale, cudaStream_t stream) { - const dim3 gridSize((in.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (in.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - convert_kernel<float,int><<<gridSize, blockSize, 0, stream>>>(in, out, scale); -} - -void ftl::cuda::int_to_float(const ftl::cuda::TextureObject<int> &in, ftl::cuda::TextureObject<float> &out, float scale, cudaStream_t stream) { - const dim3 gridSize((in.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (in.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - convert_kernel<int,float><<<gridSize, blockSize, 0, stream>>>(in, out, scale); -} - -/// ===== Median Filter ====== - -#define WINDOW_SIZE 3 -#define MEDIAN_RADIUS 3 -#define MEDIAN_SIZE (((MEDIAN_RADIUS*2)+1)*((MEDIAN_RADIUS*2)+1)) - -__global__ void medianFilterKernel(TextureObject<int> inputImageKernel, TextureObject<float> outputImagekernel) -{ - // Set row and colum for thread. - int row = blockIdx.y * blockDim.y + threadIdx.y; - int col = blockIdx.x * blockDim.x + threadIdx.x; - int filterVector[MEDIAN_SIZE] = {0}; //Take fiter window - if((row<=MEDIAN_RADIUS) || (col<=MEDIAN_RADIUS) || (row>=inputImageKernel.height()-MEDIAN_RADIUS) || (col>=inputImageKernel.width()-MEDIAN_RADIUS)) - outputImagekernel(col, row) = 0.0f; //Deal with boundry conditions - else { - for (int v = -MEDIAN_RADIUS; v <= MEDIAN_RADIUS; v++) { - for (int u = -MEDIAN_RADIUS; u <= MEDIAN_RADIUS; u++){ - filterVector[(v+MEDIAN_RADIUS)*(2*MEDIAN_RADIUS+1)+u+MEDIAN_RADIUS] = inputImageKernel((col+u), (row+v)); // setup the filterign window. - } - } - for (int i = 0; i < MEDIAN_SIZE; i++) { - for (int j = i + 1; j < MEDIAN_SIZE; j++) { - if (filterVector[i] > filterVector[j]) { - //Swap the variables. - char tmp = filterVector[i]; - filterVector[i] = filterVector[j]; - filterVector[j] = tmp; - } - } - } - outputImagekernel(col, row) = (float)filterVector[MEDIAN_SIZE/2+1] / 1000.0f; //Set the output variables. - } -} - -void ftl::cuda::median_filter(const ftl::cuda::TextureObject<int> &in, ftl::cuda::TextureObject<float> &out, cudaStream_t stream) { - const dim3 gridSize((in.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (in.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - medianFilterKernel<<<gridSize, blockSize, 0, stream>>>(in, out); -} - - -/// ===== Hole Fill ===== - -__device__ inline float distance2(float3 a, float3 b) { - const float x = a.x-b.x; - const float y = a.y-b.y; - const float z = a.z-b.z; - return x*x+y*y+z*z; -} - -#define SPLAT_RADIUS 7 -#define SPLAT_BOUNDS (2*SPLAT_RADIUS+T_PER_BLOCK+1) -#define SPLAT_BUFFER_SIZE (SPLAT_BOUNDS*SPLAT_BOUNDS) - -__global__ void hole_fill_kernel( - TextureObject<int> depth_in, - TextureObject<float> depth_out, DepthCameraParams params) { - // Read an NxN region and - // - interpolate a depth value for this pixel - // - interpolate an rgb value for this pixel - // Must respect depth discontinuities. - // How much influence a given neighbour has depends on its depth value - - __shared__ float3 positions[SPLAT_BUFFER_SIZE]; - - const float voxelSize = c_hashParams.m_virtualVoxelSize; - - const int i = threadIdx.y*blockDim.y + threadIdx.x; - const int bx = blockIdx.x*blockDim.x; - const int by = blockIdx.y*blockDim.y; - const int x = bx + threadIdx.x; - const int y = by + threadIdx.y; - - // const float camMinDepth = params.camera.m_sensorDepthWorldMin; - // const float camMaxDepth = params.camera.m_sensorDepthWorldMax; - - for (int j=i; j<SPLAT_BUFFER_SIZE; j+=T_PER_BLOCK) { - const unsigned int sx = (j % SPLAT_BOUNDS)+bx-SPLAT_RADIUS; - const unsigned int sy = (j / SPLAT_BOUNDS)+by-SPLAT_RADIUS; - if (sx >= depth_in.width() || sy >= depth_in.height()) { - positions[j] = make_float3(1000.0f,1000.0f, 1000.0f); - } else { - positions[j] = params.kinectDepthToSkeleton(sx, sy, (float)depth_in.tex2D((int)sx,(int)sy) / 1000.0f); - } - } - - __syncthreads(); - - if (x >= depth_in.width() || y >= depth_in.height()) return; - - const float voxelSquared = voxelSize*voxelSize; - float mindepth = 1000.0f; - //int minidx = -1; - // float3 minpos; - - //float3 validPos[MAX_VALID]; - //int validIndices[MAX_VALID]; - //int validix = 0; - - for (int v=-SPLAT_RADIUS; v<=SPLAT_RADIUS; ++v) { - for (int u=-SPLAT_RADIUS; u<=SPLAT_RADIUS; ++u) { - //const int idx = (threadIdx.y+v)*SPLAT_BOUNDS+threadIdx.x+u; - const int idx = (threadIdx.y+v+SPLAT_RADIUS)*SPLAT_BOUNDS+threadIdx.x+u+SPLAT_RADIUS; - - float3 posp = positions[idx]; - const float d = posp.z; - //if (d < camMinDepth || d > camMaxDepth) continue; - - float3 pos = params.kinectDepthToSkeleton(x, y, d); - float dist = distance2(pos, posp); - - if (dist < voxelSquared) { - // Valid so check for minimum - //validPos[validix] = pos; - //validIndices[validix++] = idx; - if (d < mindepth) { - mindepth = d; - //minidx = idx; - // minpos = pos; - } - } - } - } - - depth_out(x,y) = mindepth; -} - -void ftl::cuda::hole_fill(const TextureObject<int> &depth_in, - const TextureObject<float> &depth_out, const DepthCameraParams ¶ms, 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); - - hole_fill_kernel<<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, params); - cudaSafeCall( cudaGetLastError() ); - - #ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - #endif -} - - -/// ===== Point cloud from depth ===== - -__global__ void point_cloud_kernel(ftl::cuda::TextureObject<float4> output, DepthCameraCUDA depthCameraData) -{ - const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; - const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; - - const int width = depthCameraData.params.m_imageWidth; - const int height = depthCameraData.params.m_imageHeight; - - if (x < width && y < height) { - float depth = tex2D<float>(depthCameraData.depth, x, y); - - output(x,y) = (depth >= depthCameraData.params.m_sensorDepthWorldMin && depth <= depthCameraData.params.m_sensorDepthWorldMax) ? - make_float4(depthCameraData.pose * depthCameraData.params.kinectDepthToSkeleton(x, y, depth), 0.0f) : - make_float4(MINF, MINF, MINF, MINF); - } -} - -void ftl::cuda::point_cloud(ftl::cuda::TextureObject<float4> &output, const DepthCameraCUDA &depthCameraData, cudaStream_t stream) { - const dim3 gridSize((depthCameraData.params.m_imageWidth + T_PER_BLOCK - 1)/T_PER_BLOCK, (depthCameraData.params.m_imageHeight + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - - point_cloud_kernel<<<gridSize, blockSize, 0, stream>>>(output, depthCameraData); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); -#endif -} - -/// ===== NORMALS ===== - - -__global__ void compute_normals_kernel(const ftl::cuda::TextureObject<float> input, ftl::cuda::TextureObject<float4> output, DepthCameraCUDA camera) -{ - const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; - const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; - - const int width = output.width(); - - if(x >= output.width() || y >= output.height()) return; - - output(x,y) = make_float4(MINF, MINF, MINF, MINF); - - if(x > 0 && x < output.width()-1 && y > 0 && y < output.height()-1) - { - const float3 CC = camera.pose * camera.params.kinectDepthToSkeleton(x,y,input(x,y)); //input[(y+0)*width+(x+0)]; - const float3 PC = camera.pose * camera.params.kinectDepthToSkeleton(x,y,input(x,y+1)); //input[(y+1)*width+(x+0)]; - const float3 CP = camera.pose * camera.params.kinectDepthToSkeleton(x,y,input(x+1,y)); //input[(y+0)*width+(x+1)]; - const float3 MC = camera.pose * camera.params.kinectDepthToSkeleton(x,y,input(x,y-1)); //input[(y-1)*width+(x+0)]; - const float3 CM = camera.pose * camera.params.kinectDepthToSkeleton(x,y,input(x-1,y)); //input[(y+0)*width+(x-1)]; - - if(CC.x != MINF && PC.x != MINF && CP.x != MINF && MC.x != MINF && CM.x != MINF) - { - const float3 n = cross(PC-MC, CP-CM); - const float l = length(n); - - if(l > 0.0f) - { - //if (x == 400 && y == 200) printf("Cam NORMX: %f\n", (n/-l).x); - output(x,y) = make_float4(n.x/-l, n.y/-l, n.z/-l, 0.0f); //make_float4(n/-l, 1.0f); - } - } - } -} - -void ftl::cuda::compute_normals(const ftl::cuda::TextureObject<float> &input, ftl::cuda::TextureObject<float4> &output, const DepthCameraCUDA &camera, cudaStream_t stream) { - const dim3 gridSize((output.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (output.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - - compute_normals_kernel<<<gridSize, blockSize, 0, stream>>>(input, output, camera); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif -} \ No newline at end of file diff --git a/applications/reconstruct/src/depth_camera_cuda.hpp b/applications/reconstruct/src/depth_camera_cuda.hpp deleted file mode 100644 index 26bfcad73f5ae72f20cfe2dd29d0e91c62fca62b..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/depth_camera_cuda.hpp +++ /dev/null @@ -1,37 +0,0 @@ -#ifndef _FTL_RECONSTRUCTION_CAMERA_CUDA_HPP_ -#define _FTL_RECONSTRUCTION_CAMERA_CUDA_HPP_ - -#include <ftl/depth_camera.hpp> -#include <ftl/voxel_hash.hpp> -#include "splat_params.hpp" - -namespace ftl { -namespace cuda { - -void clear_depth(const TextureObject<float> &depth, cudaStream_t stream); -void clear_depth(const TextureObject<int> &depth, cudaStream_t stream); -void clear_to_zero(const ftl::cuda::TextureObject<float> &depth, cudaStream_t stream); -void clear_points(const ftl::cuda::TextureObject<float4> &depth, cudaStream_t stream); -void clear_colour(const ftl::cuda::TextureObject<uchar4> &depth, cudaStream_t stream); -void clear_colour(const ftl::cuda::TextureObject<float4> &depth, cudaStream_t stream); - -void median_filter(const ftl::cuda::TextureObject<int> &in, ftl::cuda::TextureObject<float> &out, cudaStream_t stream); - -void int_to_float(const ftl::cuda::TextureObject<int> &in, ftl::cuda::TextureObject<float> &out, float scale, cudaStream_t stream); - -void float_to_int(const ftl::cuda::TextureObject<float> &in, ftl::cuda::TextureObject<int> &out, float scale, cudaStream_t stream); - -void mls_smooth(TextureObject<float4> &output, const ftl::voxhash::HashParams &hashParams, int numcams, int cam, cudaStream_t stream); - -void mls_render_depth(const TextureObject<int> &input, TextureObject<int> &output, const ftl::render::SplatParams ¶ms, int numcams, cudaStream_t stream); - -void hole_fill(const TextureObject<int> &depth_in, const TextureObject<float> &depth_out, const DepthCameraParams ¶ms, cudaStream_t stream); - -void point_cloud(ftl::cuda::TextureObject<float4> &output, const ftl::voxhash::DepthCameraCUDA &depthCameraData, cudaStream_t stream); - -void compute_normals(const ftl::cuda::TextureObject<float> &depth, ftl::cuda::TextureObject<float4> &normals, const ftl::voxhash::DepthCameraCUDA &camera, cudaStream_t stream); - -} -} - -#endif // _FTL_RECONSTRUCTION_CAMERA_CUDA_HPP_ diff --git a/applications/reconstruct/src/point_cloud.hpp b/applications/reconstruct/src/point_cloud.hpp deleted file mode 100644 index 7b5f49c07ea5826736feb861bcd42f133367c291..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/point_cloud.hpp +++ /dev/null @@ -1,36 +0,0 @@ -#ifndef _FTL_POINT_CLOUD_HPP_ -#define _FTL_POINT_CLOUD_HPP_ - -namespace ftl { -namespace pointcloud { - - -struct VoxelPoint { - union { - uint64_t val; - struct { - uint16_t x : 12; // Block X - uint16_t y : 12; // Block Y - uint16_t z : 12; // Block Z - uint16_t v : 9; // Voxel offset in block 0-511 - }; - }; -}; - -struct VoxelColour { - union { - uint32_t val; - struct { - uint8_t b; - uint8_t g; - uint8_t r; - uint8_t a; - }; - }; -}; - - -} -} - -#endif // _FTL_POINT_CLOUD_HPP_ diff --git a/applications/reconstruct/src/ray_cast_sdf.cpp b/applications/reconstruct/src/ray_cast_sdf.cpp deleted file mode 100644 index 1c12a762cd56b82d8dd8be585c0fe75733b010f5..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/ray_cast_sdf.cpp +++ /dev/null @@ -1,106 +0,0 @@ -//#include <stdafx.h> - -#include <ftl/voxel_hash.hpp> -#include "compactors.hpp" -#include "splat_render_cuda.hpp" - -//#include "Util.h" - -#include <ftl/ray_cast_sdf.hpp> - - -extern "C" void renderCS( - const ftl::voxhash::HashData& hashData, - const RayCastData &rayCastData, - const RayCastParams &rayCastParams, cudaStream_t stream); - -extern "C" void computeNormals(float4* d_output, float3* d_input, unsigned int width, unsigned int height); -extern "C" void convertDepthFloatToCameraSpaceFloat3(float3* d_output, float* d_input, float4x4 intrinsicsInv, unsigned int width, unsigned int height, const DepthCameraData& depthCameraData); - -extern "C" void resetRayIntervalSplatCUDA(RayCastData& data, const RayCastParams& params); -extern "C" void rayIntervalSplatCUDA(const ftl::voxhash::HashData& hashData, - const RayCastData &rayCastData, const RayCastParams &rayCastParams); - -extern "C" void nickRenderCUDA(const ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, const RayCastData &rayCastData, const RayCastParams ¶ms, cudaStream_t stream); - - - -void CUDARayCastSDF::create(const RayCastParams& params) -{ - m_params = params; - m_data.allocate(m_params); - //m_rayIntervalSplatting.OnD3D11CreateDevice(DXUTGetD3D11Device(), params.m_width, params.m_height); -} - -void CUDARayCastSDF::destroy(void) -{ - m_data.free(); - //m_rayIntervalSplatting.OnD3D11DestroyDevice(); -} - -//extern "C" unsigned int compactifyHashAllInOneCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams); - - -void CUDARayCastSDF::compactifyHashEntries(ftl::voxhash::HashData& hashData, ftl::voxhash::HashParams& hashParams, cudaStream_t stream) { //const DepthCameraData& depthCameraData) { - - ftl::cuda::compactifyVisible(hashData, hashParams, m_params.camera, stream); //this version uses atomics over prefix sums, which has a much better performance - //std::cout << "Ray blocks = " << hashParams.m_numOccupiedBlocks << std::endl; - //hashData.updateParams(hashParams); //make sure numOccupiedBlocks is updated on the GPU -} - -void CUDARayCastSDF::render(ftl::voxhash::HashData& hashData, ftl::voxhash::HashParams& hashParams, const DepthCameraParams& cameraParams, const Eigen::Matrix4f& lastRigidTransform, cudaStream_t stream) -{ - //updateConstantDepthCameraParams(cameraParams); - //rayIntervalSplatting(hashData, hashParams, lastRigidTransform); - //m_data.d_rayIntervalSplatMinArray = m_rayIntervalSplatting.mapMinToCuda(); - //m_data.d_rayIntervalSplatMaxArray = m_rayIntervalSplatting.mapMaxToCuda(); - - m_params.camera = cameraParams; - //m_params.m_numOccupiedSDFBlocks = hashParams.m_numOccupiedBlocks; - m_params.m_viewMatrix = MatrixConversion::toCUDA(lastRigidTransform.inverse()); - m_params.m_viewMatrixInverse = MatrixConversion::toCUDA(lastRigidTransform); - //m_data.updateParams(m_params); - - compactifyHashEntries(hashData, hashParams, stream); - - if (hash_render_) { - //ftl::cuda::isosurface_point_image(hashData, hashParams, m_data, m_params, stream); - } else renderCS(hashData, m_data, m_params, stream); - - //convertToCameraSpace(cameraData); - //if (!m_params.m_useGradients) - //{ - // computeNormals(m_data.d_normals, m_data.d_depth3, m_params.m_width, m_params.m_height); - //} - - //m_rayIntervalSplatting.unmapCuda(); - -} - - -/*void CUDARayCastSDF::convertToCameraSpace(const DepthCameraData& cameraData) -{ - convertDepthFloatToCameraSpaceFloat3(m_data.d_depth3, m_data.d_depth, m_params.m_intrinsicsInverse, m_params.m_width, m_params.m_height, cameraData); - - if(!m_params.m_useGradients) { - computeNormals(m_data.d_normals, m_data.d_depth3, m_params.m_width, m_params.m_height); - } -}*/ - -/*void CUDARayCastSDF::rayIntervalSplatting(const ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, const Eigen::Matrix4f& lastRigidTransform) -{ - if (hashParams.m_numOccupiedBlocks == 0) return; - - if (m_params.m_maxNumVertices <= 6*hashParams.m_numOccupiedBlocks) { // 6 verts (2 triangles) per block - throw std::runtime_error("not enough space for vertex buffer for ray interval splatting"); - } - - m_params.m_numOccupiedSDFBlocks = hashParams.m_numOccupiedBlocks; - m_params.m_viewMatrix = MatrixConversion::toCUDA(lastRigidTransform.inverse()); - m_params.m_viewMatrixInverse = MatrixConversion::toCUDA(lastRigidTransform); - - m_data.updateParams(m_params); // !!! debugging - - //don't use ray interval splatting (cf CUDARayCastSDF.cu -> line 40 - //m_rayIntervalSplatting.rayIntervalSplatting(DXUTGetD3D11DeviceContext(), hashData, cameraData, m_data, m_params, m_params.m_numOccupiedSDFBlocks*6); -}*/ \ No newline at end of file diff --git a/applications/reconstruct/src/ray_cast_sdf.cu b/applications/reconstruct/src/ray_cast_sdf.cu deleted file mode 100644 index 10fd3e0b7b84ca694432abc7dc68fc513ad483eb..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/ray_cast_sdf.cu +++ /dev/null @@ -1,189 +0,0 @@ - -//#include <cuda_runtime.h> - -#include <ftl/cuda_matrix_util.hpp> - -#include <ftl/depth_camera.hpp> -#include <ftl/voxel_hash.hpp> -#include <ftl/ray_cast_util.hpp> - -#define T_PER_BLOCK 8 -#define NUM_GROUPS_X 1024 - -#define NUM_CUDA_BLOCKS 10000 - -//texture<float, cudaTextureType2D, cudaReadModeElementType> rayMinTextureRef; -//texture<float, cudaTextureType2D, cudaReadModeElementType> rayMaxTextureRef; - -__global__ void renderKernel(ftl::voxhash::HashData hashData, RayCastData rayCastData, RayCastParams rayCastParams) -{ - const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; - const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; - - //const RayCastParams& rayCastParams = c_rayCastParams; - - if (x < rayCastParams.m_width && y < rayCastParams.m_height) { - rayCastData.d_depth[y*rayCastParams.m_width+x] = MINF; - rayCastData.d_depth3[y*rayCastParams.m_width+x] = make_float3(MINF,MINF,MINF); - rayCastData.d_normals[y*rayCastParams.m_width+x] = make_float4(MINF,MINF,MINF,MINF); - rayCastData.d_colors[y*rayCastParams.m_width+x] = make_uchar3(0,0,0); - - float3 camDir = normalize(rayCastParams.camera.kinectProjToCamera(x, y, 1.0f)); - float3 worldCamPos = rayCastParams.m_viewMatrixInverse * make_float3(0.0f, 0.0f, 0.0f); - float4 w = rayCastParams.m_viewMatrixInverse * make_float4(camDir, 0.0f); - float3 worldDir = normalize(make_float3(w.x, w.y, w.z)); - - ////use ray interval splatting - //float minInterval = tex2D(rayMinTextureRef, x, y); - //float maxInterval = tex2D(rayMaxTextureRef, x, y); - - //don't use ray interval splatting - float minInterval = rayCastParams.m_minDepth; - float maxInterval = rayCastParams.m_maxDepth; - - //if (minInterval == 0 || minInterval == MINF) minInterval = rayCastParams.m_minDepth; - //if (maxInterval == 0 || maxInterval == MINF) maxInterval = rayCastParams.m_maxDepth; - //TODO MATTHIAS: shouldn't this return in the case no interval is found? - if (minInterval == 0 || minInterval == MINF) return; - if (maxInterval == 0 || maxInterval == MINF) return; - - // debugging - //if (maxInterval < minInterval) { - // printf("ERROR (%d,%d): [ %f, %f ]\n", x, y, minInterval, maxInterval); - //} - - rayCastData.traverseCoarseGridSimpleSampleAll(hashData, rayCastParams, worldCamPos, worldDir, camDir, make_int3(x,y,1), minInterval, maxInterval); - } -} - -extern "C" void renderCS(const ftl::voxhash::HashData& hashData, const RayCastData &rayCastData, const RayCastParams &rayCastParams, cudaStream_t stream) -{ - - const dim3 gridSize((rayCastParams.m_width + T_PER_BLOCK - 1)/T_PER_BLOCK, (rayCastParams.m_height + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - - //cudaChannelFormatDesc channelDesc = cudaCreateChannelDesc(32, 0, 0, 0, cudaChannelFormatKindFloat); - //cudaBindTextureToArray(rayMinTextureRef, rayCastData.d_rayIntervalSplatMinArray, channelDesc); - //cudaBindTextureToArray(rayMaxTextureRef, rayCastData.d_rayIntervalSplatMaxArray, channelDesc); - - //printf("Ray casting render...\n"); - - renderKernel<<<gridSize, blockSize, 0, stream>>>(hashData, rayCastData, rayCastParams); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif -} - - -///////////////////////////////////////////////////////////////////////// -// ray interval splatting -///////////////////////////////////////////////////////////////////////// - -/*__global__ void resetRayIntervalSplatKernel(RayCastData data) -{ - uint idx = blockIdx.x + blockIdx.y * NUM_GROUPS_X; - data.point_cloud_[idx] = make_float3(MINF); -} - -extern "C" void resetRayIntervalSplatCUDA(RayCastData& data, const RayCastParams& params) -{ - const dim3 gridSize(NUM_GROUPS_X, (params.m_maxNumVertices + NUM_GROUPS_X - 1) / NUM_GROUPS_X, 1); // ! todo check if need third dimension? - const dim3 blockSize(1, 1, 1); - - resetRayIntervalSplatKernel<<<gridSize, blockSize>>>(data); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif -}*/ - -/*__global__ void rayIntervalSplatKernel(ftl::voxhash::HashData hashData, DepthCameraData depthCameraData, RayCastData rayCastData, DepthCameraData cameraData) -{ - uint idx = blockIdx.x + blockIdx.y * NUM_GROUPS_X; - - const ftl::voxhash::HashEntry& entry = hashData.d_hashCompactified[idx]; - if (entry.ptr != ftl::voxhash::FREE_ENTRY) { - //if (!hashData.isSDFBlockInCameraFrustumApprox(entry.pos)) return; - const RayCastParams ¶ms = c_rayCastParams; - const float4x4& viewMatrix = params.m_viewMatrix; - - float3 worldCurrentVoxel = hashData.SDFBlockToWorld(entry.pos); - - float3 MINV = worldCurrentVoxel - c_hashParams.m_virtualVoxelSize / 2.0f; - - float3 maxv = MINV+SDF_BLOCK_SIZE*c_hashParams.m_virtualVoxelSize; - - float3 proj000 = cameraData.cameraToKinectProj(viewMatrix * make_float3(MINV.x, MINV.y, MINV.z)); - float3 proj100 = cameraData.cameraToKinectProj(viewMatrix * make_float3(maxv.x, MINV.y, MINV.z)); - float3 proj010 = cameraData.cameraToKinectProj(viewMatrix * make_float3(MINV.x, maxv.y, MINV.z)); - float3 proj001 = cameraData.cameraToKinectProj(viewMatrix * make_float3(MINV.x, MINV.y, maxv.z)); - float3 proj110 = cameraData.cameraToKinectProj(viewMatrix * make_float3(maxv.x, maxv.y, MINV.z)); - float3 proj011 = cameraData.cameraToKinectProj(viewMatrix * make_float3(MINV.x, maxv.y, maxv.z)); - float3 proj101 = cameraData.cameraToKinectProj(viewMatrix * make_float3(maxv.x, MINV.y, maxv.z)); - float3 proj111 = cameraData.cameraToKinectProj(viewMatrix * make_float3(maxv.x, maxv.y, maxv.z)); - - // Tree Reduction Min - float3 min00 = fminf(proj000, proj100); - float3 min01 = fminf(proj010, proj001); - float3 min10 = fminf(proj110, proj011); - float3 min11 = fminf(proj101, proj111); - - float3 min0 = fminf(min00, min01); - float3 min1 = fminf(min10, min11); - - float3 minFinal = fminf(min0, min1); - - // Tree Reduction Max - float3 max00 = fmaxf(proj000, proj100); - float3 max01 = fmaxf(proj010, proj001); - float3 max10 = fmaxf(proj110, proj011); - float3 max11 = fmaxf(proj101, proj111); - - float3 max0 = fmaxf(max00, max01); - float3 max1 = fmaxf(max10, max11); - - float3 maxFinal = fmaxf(max0, max1); - - float depth = maxFinal.z; - if(params.m_splatMinimum == 1) { - depth = minFinal.z; - } - float depthWorld = cameraData.kinectProjToCameraZ(depth); - - //uint addr = idx*4; - //rayCastData.d_vertexBuffer[addr] = make_float4(maxFinal.x, minFinal.y, depth, depthWorld); - //rayCastData.d_vertexBuffer[addr+1] = make_float4(minFinal.x, minFinal.y, depth, depthWorld); - //rayCastData.d_vertexBuffer[addr+2] = make_float4(maxFinal.x, maxFinal.y, depth, depthWorld); - //rayCastData.d_vertexBuffer[addr+3] = make_float4(minFinal.x, maxFinal.y, depth, depthWorld); - - // Note (Nick) : Changed to create point cloud instead of vertex. - uint addr = idx; - rayCastData.point_cloud_[addr] = make_float3(maxFinal.x, maxFinal.y, depth); - //printf("Ray: %f\n", depth); - - uint addr = idx*6; - rayCastData.d_vertexBuffer[addr] = make_float4(maxFinal.x, minFinal.y, depth, depthWorld); - rayCastData.d_vertexBuffer[addr+1] = make_float4(minFinal.x, minFinal.y, depth, depthWorld); - rayCastData.d_vertexBuffer[addr+2] = make_float4(maxFinal.x, maxFinal.y, depth, depthWorld); - rayCastData.d_vertexBuffer[addr+3] = make_float4(minFinal.x, minFinal.y, depth, depthWorld); - rayCastData.d_vertexBuffer[addr+4] = make_float4(maxFinal.x, maxFinal.y, depth, depthWorld); - rayCastData.d_vertexBuffer[addr+5] = make_float4(minFinal.x, maxFinal.y, depth, depthWorld); - } -} - -extern "C" void rayIntervalSplatCUDA(const ftl::voxhash::HashData& hashData, const DepthCameraData& cameraData, const RayCastData &rayCastData, const RayCastParams &rayCastParams) -{ - //printf("Ray casting...\n"); - const dim3 gridSize(NUM_GROUPS_X, (rayCastParams.m_numOccupiedSDFBlocks + NUM_GROUPS_X - 1) / NUM_GROUPS_X, 1); - const dim3 blockSize(1, 1, 1); - - rayIntervalSplatKernel<<<gridSize, blockSize>>>(hashData, cameraData, rayCastData, cameraData); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif -} */ diff --git a/applications/reconstruct/src/scene_rep_hash_sdf.cu b/applications/reconstruct/src/scene_rep_hash_sdf.cu deleted file mode 100644 index 4750d3e7ed4f7aeb68875e0b5050d76efed5b715..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/scene_rep_hash_sdf.cu +++ /dev/null @@ -1,282 +0,0 @@ -// From: https://github.com/niessner/VoxelHashing/blob/master/DepthSensingCUDA/Source/CUDASceneRepHashSDF.cu - -//#include <cutil_inline.h> -//#include <cutil_math.h> -//#include <vector_types.h> -//#include <cuda_runtime.h> - -#include <ftl/cuda_matrix_util.hpp> - -#include <ftl/voxel_hash.hpp> -#include <ftl/depth_camera.hpp> -#include <ftl/ray_cast_params.hpp> - -#define T_PER_BLOCK 8 - -using ftl::voxhash::HashData; -using ftl::voxhash::HashParams; -using ftl::voxhash::Voxel; -using ftl::voxhash::HashEntry; -using ftl::voxhash::FREE_ENTRY; - -// TODO (Nick) Use ftl::cuda::Texture (texture objects) -//texture<float, cudaTextureType2D, cudaReadModeElementType> depthTextureRef; -//texture<float4, cudaTextureType2D, cudaReadModeElementType> colorTextureRef; - -__device__ __constant__ HashParams c_hashParams; -__device__ __constant__ RayCastParams c_rayCastParams; -//__device__ __constant__ DepthCameraParams c_depthCameraParams; -__device__ __constant__ ftl::voxhash::DepthCameraCUDA c_cameras[MAX_CAMERAS]; - -extern "C" void updateConstantHashParams(const HashParams& params) { - - size_t size; - cudaSafeCall(cudaGetSymbolSize(&size, c_hashParams)); - cudaSafeCall(cudaMemcpyToSymbol(c_hashParams, ¶ms, size, 0, cudaMemcpyHostToDevice)); - -#ifdef DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif - } - - -/*extern "C" void updateConstantRayCastParams(const RayCastParams& params) { - //printf("Update ray cast params\n"); - size_t size; - cudaSafeCall(cudaGetSymbolSize(&size, c_rayCastParams)); - cudaSafeCall(cudaMemcpyToSymbol(c_rayCastParams, ¶ms, size, 0, cudaMemcpyHostToDevice)); - -#ifdef DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif - -}*/ - -extern "C" void updateCUDACameraConstant(ftl::voxhash::DepthCameraCUDA *data, int count) { - if (count == 0 || count >= MAX_CAMERAS) return; - //printf("Update depth camera params\n"); - size_t size; - cudaSafeCall(cudaGetSymbolSize(&size, c_cameras)); - cudaSafeCall(cudaMemcpyToSymbol(c_cameras, data, sizeof(ftl::voxhash::DepthCameraCUDA)*count, 0, cudaMemcpyHostToDevice)); - -#ifdef DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif - -} - -/*__global__ void resetHeapKernel(HashData hashData) -{ - const HashParams& hashParams = c_hashParams; - unsigned int idx = blockIdx.x*blockDim.x + threadIdx.x; - - if (idx == 0) { - hashData.d_heapCounter[0] = hashParams.m_numSDFBlocks - 1; //points to the last element of the array - } - - if (idx < hashParams.m_numSDFBlocks) { - - hashData.d_heap[idx] = hashParams.m_numSDFBlocks - idx - 1; - uint blockSize = SDF_BLOCK_SIZE * SDF_BLOCK_SIZE * SDF_BLOCK_SIZE; - uint base_idx = idx * blockSize; - for (uint i = 0; i < blockSize; i++) { - hashData.deleteVoxel(base_idx+i); - } - } -}*/ - -__global__ void resetHashKernel(HashData hashData) -{ - const HashParams& hashParams = c_hashParams; - const unsigned int idx = blockIdx.x*blockDim.x + threadIdx.x; - if (idx < hashParams.m_hashNumBuckets) { - hashData.deleteHashEntry(hashData.d_hash[idx]); - //hashData.deleteHashEntry(hashData.d_hashCompactified[idx]); - } -} - - -__global__ void resetHashBucketMutexKernel(HashData hashData) -{ - const HashParams& hashParams = c_hashParams; - const unsigned int idx = blockIdx.x*blockDim.x + threadIdx.x; - if (idx < hashParams.m_hashNumBuckets) { - hashData.d_hashBucketMutex[idx] = FREE_ENTRY; - } -} - -extern "C" void resetCUDA(HashData& hashData, const HashParams& hashParams) -{ - //{ - //resetting the heap and SDF blocks - //const dim3 gridSize((hashParams.m_numSDFBlocks + (T_PER_BLOCK*T_PER_BLOCK) - 1)/(T_PER_BLOCK*T_PER_BLOCK), 1); - //const dim3 blockSize((T_PER_BLOCK*T_PER_BLOCK), 1); - - //resetHeapKernel<<<gridSize, blockSize>>>(hashData); - - - //#ifdef _DEBUG - // cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); - //#endif - - //} - - { - //resetting the hash - const dim3 gridSize((hashParams.m_hashNumBuckets + (T_PER_BLOCK*T_PER_BLOCK) - 1)/(T_PER_BLOCK*T_PER_BLOCK), 1); - const dim3 blockSize((T_PER_BLOCK*T_PER_BLOCK), 1); - - resetHashKernel<<<gridSize, blockSize>>>(hashData); - - #ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); - #endif - } - - { - //resetting the mutex - const dim3 gridSize((hashParams.m_hashNumBuckets + (T_PER_BLOCK*T_PER_BLOCK) - 1)/(T_PER_BLOCK*T_PER_BLOCK), 1); - const dim3 blockSize((T_PER_BLOCK*T_PER_BLOCK), 1); - - resetHashBucketMutexKernel<<<gridSize, blockSize>>>(hashData); - - #ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); - #endif - } - - -} - -extern "C" void resetHashBucketMutexCUDA(HashData& hashData, const HashParams& hashParams, cudaStream_t stream) -{ - const dim3 gridSize((hashParams.m_hashNumBuckets + (T_PER_BLOCK*T_PER_BLOCK) - 1)/(T_PER_BLOCK*T_PER_BLOCK), 1); - const dim3 blockSize((T_PER_BLOCK*T_PER_BLOCK), 1); - - resetHashBucketMutexKernel<<<gridSize, blockSize, 0, stream>>>(hashData); - -#ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); -#endif -} - - -// Note: bitMask used for Streaming out code... could be set to nullptr if not streaming out -// Note: Allocations might need to be around fat rays since multiple voxels could correspond -// to same depth map pixel at larger distances. -__global__ void allocKernel(HashData hashData, HashParams hashParams, int camnum) -{ - //const HashParams& hashParams = c_hashParams; - const ftl::voxhash::DepthCameraCUDA camera = c_cameras[camnum]; - const DepthCameraParams &cameraParams = camera.params; - - const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; - const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; - - if (x < cameraParams.m_imageWidth && y < cameraParams.m_imageHeight) - { - float d = tex2D<float>(camera.depth, x, y); - //if (d == MINF || d < cameraParams.m_sensorDepthWorldMin || d > cameraParams.m_sensorDepthWorldMax) return; - if (d == MINF || d == 0.0f) return; - - if (d >= hashParams.m_maxIntegrationDistance) return; - - // TODO (Nick) Use covariance to include a frustrum of influence - float t = hashData.getTruncation(d); - float minDepth = min(hashParams.m_maxIntegrationDistance, d-t); - float maxDepth = min(hashParams.m_maxIntegrationDistance, d+t); - if (minDepth >= maxDepth) return; - - // Convert ray from image coords to world - // Does kinectDepthToSkeleton convert pixel values to coordinates using - // camera intrinsics? Same as what reprojectTo3D does in OpenCV? - float3 rayMin = cameraParams.kinectDepthToSkeleton(x, y, minDepth); - // Is the rigid transform then the estimated camera pose? - rayMin = camera.pose * rayMin; - //printf("Ray min: %f,%f,%f\n", rayMin.x, rayMin.y, rayMin.z); - float3 rayMax = cameraParams.kinectDepthToSkeleton(x, y, maxDepth); - rayMax = camera.pose * rayMax; - - float3 rayDir = normalize(rayMax - rayMin); - - // Only ray cast from min possible depth to max depth - int3 idCurrentVoxel = hashData.worldToSDFBlock(rayMin); - int3 idEnd = hashData.worldToSDFBlock(rayMax); - - float3 step = make_float3(sign(rayDir)); - float3 boundaryPos = hashData.SDFBlockToWorld(idCurrentVoxel+make_int3(clamp(step, 0.0, 1.0f)))-0.5f*hashParams.m_virtualVoxelSize; - float3 tMax = (boundaryPos-rayMin)/rayDir; - float3 tDelta = (step*SDF_BLOCK_SIZE*hashParams.m_virtualVoxelSize)/rayDir; - int3 idBound = make_int3(make_float3(idEnd)+step); - - //#pragma unroll - //for(int c = 0; c < 3; c++) { - // if (rayDir[c] == 0.0f) { tMax[c] = PINF; tDelta[c] = PINF; } - // if (boundaryPos[c] - rayMin[c] == 0.0f) { tMax[c] = PINF; tDelta[c] = PINF; } - //} - if (rayDir.x == 0.0f) { tMax.x = PINF; tDelta.x = PINF; } - if (boundaryPos.x - rayMin.x == 0.0f) { tMax.x = PINF; tDelta.x = PINF; } - - if (rayDir.y == 0.0f) { tMax.y = PINF; tDelta.y = PINF; } - if (boundaryPos.y - rayMin.y == 0.0f) { tMax.y = PINF; tDelta.y = PINF; } - - if (rayDir.z == 0.0f) { tMax.z = PINF; tDelta.z = PINF; } - if (boundaryPos.z - rayMin.z == 0.0f) { tMax.z = PINF; tDelta.z = PINF; } - - - unsigned int iter = 0; // iter < g_MaxLoopIterCount - unsigned int g_MaxLoopIterCount = 1024; -#pragma unroll 1 - while(iter < g_MaxLoopIterCount) { - - //check if it's in the frustum and not checked out - if (hashData.isInBoundingBox(hashParams, idCurrentVoxel)) { //} && !isSDFBlockStreamedOut(idCurrentVoxel, hashData, d_bitMask)) { - hashData.allocBlock(idCurrentVoxel); - //printf("Allocate block: %d\n",idCurrentVoxel.x); - } - - // Traverse voxel grid - if(tMax.x < tMax.y && tMax.x < tMax.z) { - idCurrentVoxel.x += step.x; - if(idCurrentVoxel.x == idBound.x) return; - tMax.x += tDelta.x; - } - else if(tMax.z < tMax.y) { - idCurrentVoxel.z += step.z; - if(idCurrentVoxel.z == idBound.z) return; - tMax.z += tDelta.z; - } - else { - idCurrentVoxel.y += step.y; - if(idCurrentVoxel.y == idBound.y) return; - tMax.y += tDelta.y; - } - - iter++; - } - } -} - -extern "C" void allocCUDA(HashData& hashData, const HashParams& hashParams, int camnum, const DepthCameraParams &depthCameraParams, cudaStream_t stream) -{ - - //printf("Allocating: %d\n",depthCameraParams.m_imageWidth); - - const dim3 gridSize((depthCameraParams.m_imageWidth + T_PER_BLOCK - 1)/T_PER_BLOCK, (depthCameraParams.m_imageHeight + T_PER_BLOCK - 1)/T_PER_BLOCK); - const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - - allocKernel<<<gridSize, blockSize, 0, stream>>>(hashData, hashParams, camnum); - - - #ifdef _DEBUG - cudaSafeCall(cudaDeviceSynchronize()); - //cutilCheckMsg(__FUNCTION__); - #endif -} diff --git a/applications/reconstruct/src/virtual_source.cpp b/applications/reconstruct/src/virtual_source.cpp deleted file mode 100644 index c8dc380743373c591ffcfcea6aae0f713c1068c1..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/virtual_source.cpp +++ /dev/null @@ -1,89 +0,0 @@ -#include <ftl/virtual_source.hpp> -#include <ftl/depth_camera.hpp> -#include <ftl/voxel_scene.hpp> -#include <ftl/ray_cast_sdf.hpp> - -#define LOGURU_WITH_STREAMS 1 -#include <loguru.hpp> - -using ftl::rgbd::VirtualSource; - -VirtualSource::VirtualSource(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host) { - rays_ = ftl::create<CUDARayCastSDF>(host, "raycaster"); //new CUDARayCastSDF(host->getConfig()); - scene_ = nullptr; - - params_.fx = rays_->value("focal", 430.0f); - params_.fy = params_.fx; - params_.width = rays_->value("width", 640); - params_.height = rays_->value("height", 480); - params_.cx = -((double)params_.width / 2); - params_.cy = -((double)params_.height / 2); - params_.maxDepth = rays_->value("max_depth", 10.0f); - params_.minDepth = rays_->value("min_depth", 0.1f); - - capabilities_ = kCapMovable | kCapVideo | kCapStereo; - - rgb_ = cv::Mat(cv::Size(params_.width,params_.height), CV_8UC3); - idepth_ = cv::Mat(cv::Size(params_.width,params_.height), CV_32SC1); - depth_ = cv::Mat(cv::Size(params_.width,params_.height), CV_32FC1); - - rays_->on("focal", [this](const ftl::config::Event &e) { - params_.fx = rays_->value("focal", 430.0f); - params_.fy = params_.fx; - }); - - rays_->on("width", [this](const ftl::config::Event &e) { - params_.width = rays_->value("width", 640); - }); - - rays_->on("height", [this](const ftl::config::Event &e) { - params_.height = rays_->value("height", 480); - }); -} - -VirtualSource::~VirtualSource() { - if (scene_) delete scene_; - if (rays_) delete rays_; -} - -void VirtualSource::setScene(ftl::voxhash::SceneRep *scene) { - scene_ = scene; -} - -bool VirtualSource::grab(int n, int b) { - if (scene_) { - // Ensure this host thread is using correct GPU. - - cudaSafeCall(cudaSetDevice(scene_->getCUDADevice())); - DepthCameraParams params; - params.fx = params_.fx; - params.fy = params_.fy; - params.mx = -params_.cx; - params.my = -params_.cy; - params.m_imageWidth = params_.width; - params.m_imageHeight = params_.height; - params.m_sensorDepthWorldMin = params_.minDepth; - params.m_sensorDepthWorldMax = params_.maxDepth; - - // TODO(Nick) Use double precision pose here - rays_->render(scene_->getHashData(), scene_->getHashParams(), params, host_->getPose().cast<float>(), scene_->getIntegrationStream()); - - //unique_lock<mutex> lk(mutex_); - if (rays_->isIntegerDepth()) { - rays_->getRayCastData().download((int*)idepth_.data, (uchar3*)rgb_.data, rays_->getRayCastParams(), scene_->getIntegrationStream()); - - cudaSafeCall(cudaStreamSynchronize(scene_->getIntegrationStream())); - idepth_.convertTo(depth_, CV_32FC1, 1.0f / 100.0f); - } else { - rays_->getRayCastData().download((int*)depth_.data, (uchar3*)rgb_.data, rays_->getRayCastParams(), scene_->getIntegrationStream()); - cudaSafeCall(cudaStreamSynchronize(scene_->getIntegrationStream())); - } - } - - return true; -} - -bool VirtualSource::isReady() { - return true; -} diff --git a/applications/reconstruct/src/voxel_scene.cpp b/applications/reconstruct/src/voxel_scene.cpp deleted file mode 100644 index 09067b1f2334e0190e27022b64d374e31532f8c2..0000000000000000000000000000000000000000 --- a/applications/reconstruct/src/voxel_scene.cpp +++ /dev/null @@ -1,466 +0,0 @@ -#include <ftl/voxel_scene.hpp> -#include "depth_camera_cuda.hpp" - -#include <opencv2/core/cuda_stream_accessor.hpp> - -#include <vector> - -using namespace ftl::voxhash; -using ftl::rgbd::Source; -using ftl::rgbd::Channel; -using ftl::Configurable; -using cv::Mat; -using std::vector; - -#define SAFE_DELETE_ARRAY(a) { delete [] (a); (a) = NULL; } - -//extern "C" void resetCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams); -//extern "C" void resetHashBucketMutexCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, cudaStream_t); -//extern "C" void allocCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, int camid, const DepthCameraParams &depthCameraParams, cudaStream_t); -//extern "C" void fillDecisionArrayCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, const DepthCameraData& depthCameraData); -//extern "C" void compactifyHashCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams); -//extern "C" unsigned int compactifyHashAllInOneCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams); -//extern "C" void integrateDepthMapCUDA(ftl::voxhash::HashData& hashData, const ftl::voxhash::HashParams& hashParams, const DepthCameraData& depthCameraData, const DepthCameraParams& depthCameraParams, cudaStream_t); -//extern "C" void bindInputDepthColorTextures(const DepthCameraData& depthCameraData); - - -SceneRep::SceneRep(nlohmann::json &config) : Configurable(config), m_frameCount(0), do_reset_(false) { - _initCUDA(); - - // Allocates voxel structure on GPU - _create(_parametersFromConfig()); - - on("SDFVoxelSize", [this](const ftl::config::Event &e) { - do_reset_ = true; - }); - on("hashNumSDFBlocks", [this](const ftl::config::Event &e) { - do_reset_ = true; - }); - on("hashNumBuckets", [this](const ftl::config::Event &e) { - do_reset_ = true; - }); - on("hashMaxCollisionLinkedListSize", [this](const ftl::config::Event &e) { - do_reset_ = true; - }); - on("SDFTruncation", [this](const ftl::config::Event &e) { - m_hashParams.m_truncation = value("SDFTruncation", 0.1f); - }); - on("SDFTruncationScale", [this](const ftl::config::Event &e) { - m_hashParams.m_truncScale = value("SDFTruncationScale", 0.01f); - }); - on("SDFMaxIntegrationDistance", [this](const ftl::config::Event &e) { - m_hashParams.m_maxIntegrationDistance = value("SDFMaxIntegrationDistance", 10.0f); - }); - on("showRegistration", [this](const ftl::config::Event &e) { - reg_mode_ = value("showRegistration", false); - }); - - reg_mode_ = value("showRegistration", false); - - cudaSafeCall(cudaStreamCreate(&integ_stream_)); - //integ_stream_ = 0; -} - -SceneRep::~SceneRep() { - _destroy(); - cudaStreamDestroy(integ_stream_); -} - -bool SceneRep::_initCUDA() { - // Do an initial CUDA check - int cuda_device_count = 0; - cudaSafeCall(cudaGetDeviceCount(&cuda_device_count)); - CHECK_GE(cuda_device_count, 1) << "No CUDA devices found"; - - LOG(INFO) << "CUDA Devices (" << cuda_device_count << "):"; - - vector<cudaDeviceProp> properties(cuda_device_count); - for (int i=0; i<cuda_device_count; i++) { - cudaSafeCall(cudaGetDeviceProperties(&properties[i], i)); - LOG(INFO) << " - " << properties[i].name; - } - - int desired_device = value("cudaDevice", 0); - cuda_device_ = (desired_device < cuda_device_count) ? desired_device : cuda_device_count-1; - cudaSafeCall(cudaSetDevice(cuda_device_)); - - // TODO:(Nick) Check memory is sufficient - // TODO:(Nick) Find out what our compute capability should be. - - LOG(INFO) << "CUDA Compute: " << properties[cuda_device_].major << "." << properties[cuda_device_].minor; - - return true; -} - -void SceneRep::addSource(ftl::rgbd::Source *src) { - auto &cam = cameras_.emplace_back(); - cam.source = src; - cam.params.m_imageWidth = 0; - src->setChannel(Channel::Depth); -} - -extern "C" void updateCUDACameraConstant(ftl::voxhash::DepthCameraCUDA *data, int count); - -void SceneRep::_updateCameraConstant() { - std::vector<ftl::voxhash::DepthCameraCUDA> cams(cameras_.size()); - for (size_t i=0; i<cameras_.size(); ++i) { - cameras_[i].gpu.data.pose = MatrixConversion::toCUDA(cameras_[i].source->getPose().cast<float>()); - cameras_[i].gpu.data.poseInverse = MatrixConversion::toCUDA(cameras_[i].source->getPose().cast<float>().inverse()); - cams[i] = cameras_[i].gpu.data; - } - updateCUDACameraConstant(cams.data(), cams.size()); -} - -int SceneRep::upload() { - int active = 0; - - for (size_t i=0; i<cameras_.size(); ++i) { - cameras_[i].source->grab(); - } - - for (size_t i=0; i<cameras_.size(); ++i) { - auto &cam = cameras_[i]; - - if (!cam.source->isReady()) { - cam.params.m_imageWidth = 0; - // TODO(Nick) : Free gpu allocs if was ready before - LOG(INFO) << "Source not ready: " << cam.source->getURI(); - continue; - } else { - auto in = cam.source; - - cam.params.fx = in->parameters().fx; - cam.params.fy = in->parameters().fy; - cam.params.mx = -in->parameters().cx; - cam.params.my = -in->parameters().cy; - - // Only now do we have camera parameters for allocations... - if (cam.params.m_imageWidth == 0) { - cam.params.m_imageWidth = in->parameters().width; - cam.params.m_imageHeight = in->parameters().height; - cam.params.m_sensorDepthWorldMax = in->parameters().maxDepth; - cam.params.m_sensorDepthWorldMin = in->parameters().minDepth; - cam.gpu.alloc(cam.params, true); - LOG(INFO) << "GPU Allocated camera " << i; - } - } - - cam.params.flags = m_frameCount; - } - - _updateCameraConstant(); - //cudaSafeCall(cudaDeviceSynchronize()); - - for (size_t i=0; i<cameras_.size(); ++i) { - auto &cam = cameras_[i]; - - // Get the RGB-Depth frame from input - Source *input = cam.source; - Mat rgb, depth; - - // TODO(Nick) Direct GPU upload to save copy - input->getFrames(rgb,depth); - - active += 1; - - if (depth.cols == 0) continue; - - // Must be in RGBA for GPU - Mat rgbt, rgba; - cv::cvtColor(rgb,rgbt, cv::COLOR_BGR2Lab); - cv::cvtColor(rgbt,rgba, cv::COLOR_BGR2BGRA); - - // Send to GPU and merge view into scene - //cam.gpu.updateParams(cam.params); - cam.gpu.updateData(depth, rgba, cam.stream); - - //setLastRigidTransform(input->getPose().cast<float>()); - - //make the rigid transform available on the GPU - //m_hashData.updateParams(m_hashParams, cv::cuda::StreamAccessor::getStream(cam.stream)); - - //if (i > 0) cudaSafeCall(cudaStreamSynchronize(cv::cuda::StreamAccessor::getStream(cameras_[i-1].stream))); - - //allocate all hash blocks which are corresponding to depth map entries - //if (value("voxels", false)) _alloc(i, cv::cuda::StreamAccessor::getStream(cam.stream)); - - // Calculate normals - } - - // Must have finished all allocations and rendering before next integration - cudaSafeCall(cudaDeviceSynchronize()); - - return active; -} - -int SceneRep::upload(ftl::rgbd::FrameSet &fs) { - int active = 0; - - for (size_t i=0; i<cameras_.size(); ++i) { - auto &cam = cameras_[i]; - - if (!cam.source->isReady()) { - cam.params.m_imageWidth = 0; - // TODO(Nick) : Free gpu allocs if was ready before - LOG(INFO) << "Source not ready: " << cam.source->getURI(); - continue; - } else { - auto in = cam.source; - - cam.params.fx = in->parameters().fx; - cam.params.fy = in->parameters().fy; - cam.params.mx = -in->parameters().cx; - cam.params.my = -in->parameters().cy; - - // Only now do we have camera parameters for allocations... - if (cam.params.m_imageWidth == 0) { - cam.params.m_imageWidth = in->parameters().width; - cam.params.m_imageHeight = in->parameters().height; - cam.params.m_sensorDepthWorldMax = in->parameters().maxDepth; - cam.params.m_sensorDepthWorldMin = in->parameters().minDepth; - cam.gpu.alloc(cam.params, true); - LOG(INFO) << "GPU Allocated camera " << i; - } - } - - cam.params.flags = m_frameCount; - } - - _updateCameraConstant(); - //cudaSafeCall(cudaDeviceSynchronize()); - - for (size_t i=0; i<cameras_.size(); ++i) { - auto &cam = cameras_[i]; - auto &chan1 = fs.frames[i].get<cv::Mat>(Channel::Colour); - auto &chan2 = fs.frames[i].get<cv::Mat>(fs.sources[i]->getChannel()); - - auto test = fs.frames[i].createTexture<uchar4>(Channel::Flow, ftl::rgbd::Format<uchar4>(100,100)); - - // Get the RGB-Depth frame from input - Source *input = cam.source; - //Mat rgb, depth; - - // TODO(Nick) Direct GPU upload to save copy - //input->getFrames(rgb,depth); - - active += 1; - - //if (depth.cols == 0) continue; - - // Must be in RGBA for GPU - Mat rgbt, rgba; - cv::cvtColor(chan1,rgbt, cv::COLOR_BGR2Lab); - cv::cvtColor(rgbt,rgba, cv::COLOR_BGR2BGRA); - - // Send to GPU and merge view into scene - //cam.gpu.updateParams(cam.params); - cam.gpu.updateData(chan2, rgba, cam.stream); - - //setLastRigidTransform(input->getPose().cast<float>()); - - //make the rigid transform available on the GPU - //m_hashData.updateParams(m_hashParams, cv::cuda::StreamAccessor::getStream(cam.stream)); - - //if (i > 0) cudaSafeCall(cudaStreamSynchronize(cv::cuda::StreamAccessor::getStream(cameras_[i-1].stream))); - - //allocate all hash blocks which are corresponding to depth map entries - //if (value("voxels", false)) _alloc(i, cv::cuda::StreamAccessor::getStream(cam.stream)); - - // Calculate normals - } - - // Must have finished all allocations and rendering before next integration - cudaSafeCall(cudaDeviceSynchronize()); - - return active; -} - -void SceneRep::integrate() { - /*for (size_t i=0; i<cameras_.size(); ++i) { - auto &cam = cameras_[i]; - - setLastRigidTransform(cam.source->getPose().cast<float>()); - //m_hashData.updateParams(m_hashParams); - - //generate a linear hash array with only occupied entries - _compactifyVisible(cam.params); - - //volumetrically integrate the depth data into the depth SDFBlocks - //_integrateDepthMap(cam.gpu, cam.params); - - //_garbageCollect(); - - m_numIntegratedFrames++; - }*/ - - _compactifyAllocated(); - _integrateDepthMaps(); -} - -void SceneRep::garbage() { - //_compactifyAllocated(); - //if (value("voxels", false)) _garbageCollect(); - - //cudaSafeCall(cudaStreamSynchronize(integ_stream_)); -} - -/*void SceneRep::integrate(const Eigen::Matrix4f& lastRigidTransform, const DepthCameraData& depthCameraData, const DepthCameraParams& depthCameraParams, unsigned int* d_bitMask) { - - setLastRigidTransform(lastRigidTransform); - - //make the rigid transform available on the GPU - m_hashData.updateParams(m_hashParams); - - //allocate all hash blocks which are corresponding to depth map entries - _alloc(depthCameraData, depthCameraParams, d_bitMask); - - //generate a linear hash array with only occupied entries - _compactifyHashEntries(); - - //volumetrically integrate the depth data into the depth SDFBlocks - _integrateDepthMap(depthCameraData, depthCameraParams); - - _garbageCollect(depthCameraData); - - m_numIntegratedFrames++; -}*/ - -/*void SceneRep::setLastRigidTransformAndCompactify(const Eigen::Matrix4f& lastRigidTransform, const DepthCameraData& depthCameraData) { - setLastRigidTransform(lastRigidTransform); - _compactifyHashEntries(); -}*/ - -/* Nick: To reduce weights between frames */ -void SceneRep::nextFrame() { - if (do_reset_) { - do_reset_ = false; - _destroy(); - _create(_parametersFromConfig()); - } else { - //ftl::cuda::compactifyAllocated(m_hashData, m_hashParams, integ_stream_); - //if (reg_mode_) ftl::cuda::clearVoxels(m_hashData, m_hashParams); - //else ftl::cuda::starveVoxels(m_hashData, m_hashParams, integ_stream_); - m_numIntegratedFrames = 0; - } -} - -//! resets the hash to the initial state (i.e., clears all data) -void SceneRep::reset() { - m_numIntegratedFrames = 0; - m_hashData.updateParams(m_hashParams); - resetCUDA(m_hashData, m_hashParams); -} - -unsigned int SceneRep::getOccupiedCount() { - unsigned int count; - cudaSafeCall(cudaMemcpy(&count, m_hashData.d_hashCompactifiedCounter, sizeof(unsigned int), cudaMemcpyDeviceToHost)); - return count+1; //there is one more free than the address suggests (0 would be also a valid address) -} - -HashParams SceneRep::_parametersFromConfig() { - //auto &cfg = ftl::config::resolve(config); - HashParams params; - // First camera view is set to identity pose to be at the centre of - // the virtual coordinate space. - params.m_hashNumBuckets = value("hashNumBuckets", 100000); - params.m_virtualVoxelSize = value("SDFVoxelSize", 0.006f); - params.m_maxIntegrationDistance = value("SDFMaxIntegrationDistance", 10.0f); - params.m_truncation = value("SDFTruncation", 0.1f); - params.m_truncScale = value("SDFTruncationScale", 0.01f); - params.m_integrationWeightSample = value("SDFIntegrationWeightSample", 10); - params.m_integrationWeightMax = value("SDFIntegrationWeightMax", 255); - params.m_spatialSmoothing = value("spatialSmoothing", 0.04f); // 4cm - params.m_colourSmoothing = value("colourSmoothing", 20.0f); - params.m_confidenceThresh = value("confidenceThreshold", 20.0f); - params.m_flags = 0; - params.m_flags |= (value("clipping", false)) ? ftl::voxhash::kFlagClipping : 0; - params.m_flags |= (value("mls", false)) ? ftl::voxhash::kFlagMLS : 0; - params.m_maxBounds = make_float3( - value("bbox_x_max", 2.0f), - value("bbox_y_max", 2.0f), - value("bbox_z_max", 2.0f)); - params.m_minBounds = make_float3( - value("bbox_x_min", -2.0f), - value("bbox_y_min", -2.0f), - value("bbox_z_min", -2.0f)); - return params; -} - -void SceneRep::_create(const HashParams& params) { - m_hashParams = params; - m_hashData.allocate(m_hashParams); - - reset(); -} - -void SceneRep::_destroy() { - m_hashData.free(); -} - -void SceneRep::_alloc(int camid, cudaStream_t stream) { - // NOTE (nick): We might want this later... - /*if (false) { - // TODO(Nick) Make this work without memcpy to host first - allocate until all blocks are allocated - unsigned int prevFree = 0; //getHeapFreeCount(); - while (1) { - resetHashBucketMutexCUDA(m_hashData, m_hashParams, stream); - allocCUDA(m_hashData, m_hashParams, camid, cameras_[camid].params, stream); - - unsigned int currFree = getHeapFreeCount(); - - if (prevFree != currFree) { - prevFree = currFree; - } - else { - break; - } - } - } - else {*/ - //this version is faster, but it doesn't guarantee that all blocks are allocated (staggers alloc to the next frame) - //resetHashBucketMutexCUDA(m_hashData, m_hashParams, stream); - //allocCUDA(m_hashData, m_hashParams, camid, cameras_[camid].params, stream); - //} -} - - -void SceneRep::_compactifyVisible(const DepthCameraParams &camera) { //const DepthCameraData& depthCameraData) { - //ftl::cuda::compactifyOccupied(m_hashData, m_hashParams, integ_stream_); //this version uses atomics over prefix sums, which has a much better performance - //m_hashData.updateParams(m_hashParams); //make sure numOccupiedBlocks is updated on the GPU -} - -void SceneRep::_compactifyAllocated() { - //ftl::cuda::compactifyAllocated(m_hashData, m_hashParams, integ_stream_); //this version uses atomics over prefix sums, which has a much better performance - //std::cout << "Occ blocks = " << m_hashParams.m_numOccupiedBlocks << std::endl; - //m_hashData.updateParams(m_hashParams); //make sure numOccupiedBlocks is updated on the GPU -} - -/*void SceneRep::_integrateDepthMap(const DepthCameraData& depthCameraData, const DepthCameraParams& depthCameraParams) { - if (!reg_mode_) ftl::cuda::integrateDepthMap(m_hashData, m_hashParams, depthCameraData, depthCameraParams, integ_stream_); - else ftl::cuda::integrateRegistration(m_hashData, m_hashParams, depthCameraData, depthCameraParams, integ_stream_); -}*/ - -//extern "C" void bilateralFilterFloatMap(float* d_output, float* d_input, float sigmaD, float sigmaR, unsigned int width, unsigned int height); - -void SceneRep::_integrateDepthMaps() { - //cudaSafeCall(cudaDeviceSynchronize()); - - for (size_t i=0; i<cameras_.size(); ++i) { - if (!cameras_[i].source->isReady()) continue; - //ftl::cuda::clear_depth(*(cameras_[i].gpu.depth2_tex_), integ_stream_); - cameras_[i].gpu.computeNormals(integ_stream_); - ftl::cuda::clear_points(*(cameras_[i].gpu.points_tex_), integ_stream_); - ftl::cuda::mls_smooth(*(cameras_[i].gpu.points_tex_), m_hashParams, cameras_.size(), i, integ_stream_); - //ftl::cuda::int_to_float(*(cameras_[i].gpu.depth2_tex_), *(cameras_[i].gpu.depth_tex_), 1.0f / 1000.0f, integ_stream_); - //ftl::cuda::hole_fill(*(cameras_[i].gpu.depth2_tex_), *(cameras_[i].gpu.depth_tex_), cameras_[i].params, integ_stream_); - //bilateralFilterFloatMap(cameras_[i].gpu.depth_tex_->devicePtr(), cameras_[i].gpu.depth3_tex_->devicePtr(), 3, 7, cameras_[i].gpu.depth_tex_->width(), cameras_[i].gpu.depth_tex_->height()); - } - //if (value("voxels", false)) ftl::cuda::integrateDepthMaps(m_hashData, m_hashParams, cameras_.size(), integ_stream_); -} - -void SceneRep::_garbageCollect() { - //ftl::cuda::garbageCollectIdentify(m_hashData, m_hashParams, integ_stream_); - //resetHashBucketMutexCUDA(m_hashData, m_hashParams, integ_stream_); //needed if linked lists are enabled -> for memeory deletion - //ftl::cuda::garbageCollectFree(m_hashData, m_hashParams, integ_stream_); -}