Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • nicolaspope/ftl
1 result
Show changes
Showing
with 1425 additions and 71 deletions
......@@ -86,6 +86,7 @@ vector<string> Master::getConfigurables() {
vector<string> Master::getConfigurables(const ftl::UUID &peer) {
try {
LOG(INFO) << "LISTING CONFIGS";
return net_->call<vector<string>>(peer, "list_configurables");
} catch (...) {
return {};
......
......@@ -9,13 +9,14 @@ add_library(ftlnet
src/dispatcher.cpp
src/universe.cpp
src/ws_internal.cpp
src/net_configurable.cpp
)
target_include_directories(ftlnet PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
PRIVATE src)
target_link_libraries(ftlnet ftlcommon Threads::Threads glog::glog ${UUID_LIBRARIES})
target_link_libraries(ftlnet ftlctrl ftlcommon Threads::Threads glog::glog ${UUID_LIBRARIES})
install(TARGETS ftlnet EXPORT ftlnet-config
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
......
#pragma once
#ifndef _FTL_NETCONFIGURABLE_HPP_
#define _FTL_NETCONFIGURABLE_HPP_
#include <ftl/configurable.hpp>
#include <ftl/master.hpp>
namespace ftl {
class NetConfigurable : public ftl::Configurable {
public:
NetConfigurable(ftl::UUID peer, const std::string &suri, ftl::ctrl::Master &ctrl, ftl::config::json_t &config);
~NetConfigurable();
protected:
void inject(const std::string name, nlohmann::json &value);
private:
ftl::UUID peer;
const std::string &suri;
ftl::ctrl::Master &ctrl;
};
}
#endif // _FTL_NETCONFIGURABLE_HPP_
#include <ftl/net_configurable.hpp>
#include <string>
ftl::NetConfigurable::NetConfigurable(ftl::UUID peer, const std::string &suri, ftl::ctrl::Master &ctrl, ftl::config::json_t &config) : ftl::Configurable(config), peer(peer), suri(suri), ctrl(ctrl) {
}
ftl::NetConfigurable::~NetConfigurable(){}
void ftl::NetConfigurable::inject(const std::string name, nlohmann::json &value) {
ctrl.set(peer, suri + std::string("/") + name, value);
}
......@@ -27,11 +27,20 @@ target_link_libraries(net_integration
Threads::Threads
${UUID_LIBRARIES})
### NetConfigurable Unit #######################################################
add_executable(net_configurable_unit
./tests.cpp
./net_configurable_unit.cpp)
target_link_libraries(net_configurable_unit
ftlnet)
#add_test(ProtocolUnitTest protocol_unit)
add_test(PeerUnitTest peer_unit)
add_test(NetIntegrationTest net_integration)
# Testing of NetConfigurable is disabled.
#add_test(NetConfigurableUnitTest net_configurable_unit)
add_custom_target(tests)
add_dependencies(tests peer_unit uri_unit)
......
#include "catch.hpp"
#include <ftl/net_configurable.hpp>
#include <ftl/slave.hpp>
using ftl::NetConfigurable;
SCENARIO( "NetConfigurable::set()" ) {
GIVEN( "valid peer UUID, URI and Master" ) {
// Set up Master
nlohmann::json json = {{"$id", "root"}, {"test", {{"listen", "tcp://localhost:7077"}}}}; // Check what values are needed
ftl::Configurable *root;
root = new ftl::Configurable(json);
ftl::net::Universe *net = ftl::config::create<ftl::net::Universe>(root, std::string("test"));
net->start();
ftl::ctrl::Master *controller = new ftl::ctrl::Master(root, net);
// Set up a slave, then call getSlaves() to get the UUID string
nlohmann::json jsonSlave = {{"$id", "slave"}, {"test", {{"peers", {"tcp://localhost:7077"}}}}};
ftl::Configurable *rootSlave;
rootSlave = new ftl::Configurable(jsonSlave);
ftl::net::Universe *netSlave = ftl::config::create<ftl::net::Universe>(rootSlave, std::string("test"));
ftl::ctrl::Slave slave(netSlave, rootSlave);
netSlave->start();
netSlave->waitConnections();
net->waitConnections();
auto slaves = controller->getSlaves();
REQUIRE( slaves.size() == 1 );
ftl::UUID peer = ftl::UUID(slaves[0]["id"].get<std::string>());
const std::string suri = "slave_test";
nlohmann::json jsonTest = {{"$id", "slave_test"}, {"test", {{"peers", {"tcp://localhost:7077"}}}}};
NetConfigurable nc(peer, suri, *controller, jsonTest);
nc.set("test_value", 5);
REQUIRE( nc.get<int>("test_value") == 5 );
}
// invalid peer UUID
// invalid URI
// null Master
}
\ No newline at end of file
add_library(ftlrender
src/splat_render.cpp
src/splatter.cpp
src/splatter.cu
src/points.cu
src/normals.cu
src/mask.cu
src/screen.cu
src/triangle_render.cu
src/reprojection.cu
src/tri_render.cpp
)
# These cause errors in CI build and are being removed from PCL in newer versions
......
#ifndef _FTL_CUDA_MAKERS_HPP_
#define _FTL_CUDA_MAKERS_HPP_
#include <ftl/cuda_common.hpp>
__device__ inline float4 make_float4(const uchar4 &c) {
return make_float4(c.x,c.y,c.z,c.w);
}
__device__ inline float4 make_float4(const float4 &v) {
return v;
}
template <typename T>
__device__ inline T make();
template <>
__device__ inline uchar4 make() {
return make_uchar4(0,0,0,0);
}
template <>
__device__ inline float4 make() {
return make_float4(0.0f,0.0f,0.0f,0.0f);
}
template <>
__device__ inline float make() {
return 0.0f;
}
template <typename T>
__device__ inline T make(const float4 &);
template <>
__device__ inline uchar4 make(const float4 &v) {
return make_uchar4((int)v.x, (int)v.y, (int)v.z, (int)v.w);
}
template <>
__device__ inline float4 make(const float4 &v) {
return v;
}
template <>
__device__ inline float make(const float4 &v) {
return v.x;
}
template <typename T>
__device__ inline T make(const uchar4 &v);
template <>
__device__ inline float4 make(const uchar4 &v) {
return make_float4((float)v.x, (float)v.y, (float)v.z, (float)v.w);
}
template <typename T>
__device__ inline T make(float v);
template <>
__device__ inline float make(float v) {
return v;
}
#endif // _FTL_CUDA_MAKERS_HPP_
#ifndef _FTL_RECONSTRUCTION_TRI_HPP_
#define _FTL_RECONSTRUCTION_TRI_HPP_
#include <ftl/render/renderer.hpp>
#include <ftl/rgbd/frameset.hpp>
#include <ftl/render/splat_params.hpp>
#include <ftl/cuda/points.hpp>
namespace ftl {
namespace render {
/**
* Generate triangles between connected points and render those. Colour is done
* by weighted reprojection to the original source images.
*/
class Triangular : public ftl::render::Renderer {
public:
explicit Triangular(nlohmann::json &config, ftl::rgbd::FrameSet *fs);
~Triangular();
bool render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) override;
//void setOutputDevice(int);
protected:
void _renderChannel(ftl::rgbd::Frame &out, ftl::codecs::Channel channel_in, ftl::codecs::Channel channel_out, cudaStream_t stream);
private:
int device_;
ftl::rgbd::Frame temp_;
ftl::rgbd::Frame accum_;
ftl::rgbd::FrameSet *scene_;
ftl::cuda::ClipSpace clip_;
bool clipping_;
float norm_filter_;
bool backcull_;
cv::Scalar background_;
bool mesh_;
float3 light_dir_;
uchar4 light_diffuse_;
uchar4 light_ambient_;
ftl::render::SplatParams params_;
cudaStream_t stream_;
float3 light_pos_;
template <typename T>
void __reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t);
void _reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t);
void _dibr(cudaStream_t);
void _mesh(cudaStream_t);
};
}
}
#endif // _FTL_RECONSTRUCTION_TRI_HPP_
......@@ -45,11 +45,11 @@ __global__ void computeNormals_kernel(ftl::cuda::TextureObject<float4> output,
output(x,y) = make_float4(0, 0, 0, 0);
if(x > 0 && x < input.width()-1 && y > 0 && y < input.height()-1) {
const float3 CC = camera.screenToCam(x+0, y+0, (float)input.tex2D((int)x+0, (int)y+0) / 1000.0f);
const float3 PC = camera.screenToCam(x+0, y+1, (float)input.tex2D((int)x+0, (int)y+1) / 1000.0f);
const float3 CP = camera.screenToCam(x+1, y+0, (float)input.tex2D((int)x+1, (int)y+0) / 1000.0f);
const float3 MC = camera.screenToCam(x+0, y-1, (float)input.tex2D((int)x+0, (int)y-1) / 1000.0f);
const float3 CM = camera.screenToCam(x-1, y+0, (float)input.tex2D((int)x-1, (int)y+0) / 1000.0f);
const float3 CC = camera.screenToCam(x+0, y+0, (float)input.tex2D((int)x+0, (int)y+0) / 100000.0f);
const float3 PC = camera.screenToCam(x+0, y+1, (float)input.tex2D((int)x+0, (int)y+1) / 100000.0f);
const float3 CP = camera.screenToCam(x+1, y+0, (float)input.tex2D((int)x+1, (int)y+0) / 100000.0f);
const float3 MC = camera.screenToCam(x+0, y-1, (float)input.tex2D((int)x+0, (int)y-1) / 100000.0f);
const float3 CM = camera.screenToCam(x-1, y+0, (float)input.tex2D((int)x-1, (int)y+0) / 100000.0f);
//if(CC.z < && PC.x != MINF && CP.x != MINF && MC.x != MINF && CM.x != MINF) {
if (isValid(camera,CC) && isValid(camera,PC) && isValid(camera,CP) && isValid(camera,MC) && isValid(camera,CM)) {
......@@ -118,7 +118,7 @@ __global__ void smooth_normals_kernel(ftl::cuda::TextureObject<float4> norms,
if(x >= depth.width() || y >= depth.height()) return;
const float3 p0 = camera.screenToCam(x,y, (float)depth.tex2D((int)x,(int)y) / 1000.0f);
const float3 p0 = camera.screenToCam(x,y, (float)depth.tex2D((int)x,(int)y) / 100000.0f);
float3 nsum = make_float3(0.0f);
float contrib = 0.0f;
......@@ -128,7 +128,7 @@ __global__ void smooth_normals_kernel(ftl::cuda::TextureObject<float4> norms,
for (int v=-RADIUS; v<=RADIUS; ++v) {
for (int u=-RADIUS; u<=RADIUS; ++u) {
const float3 p = camera.screenToCam(x+u,y+v, (float)depth.tex2D((int)x+u,(int)y+v) / 1000.0f);
const float3 p = camera.screenToCam(x+u,y+v, (float)depth.tex2D((int)x+u,(int)y+v) / 100000.0f);
if (p.z < camera.minDepth || p.z > camera.maxDepth) continue;
const float s = ftl::cuda::spatialWeighting(p0, p, smoothing);
//const float s = 1.0f;
......@@ -226,7 +226,9 @@ void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
switch (radius) {
case 7: smooth_normals_kernel<7><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
case 5: smooth_normals_kernel<5><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
case 3: smooth_normals_kernel<3><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
case 3: smooth_normals_kernel<3><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
case 2: smooth_normals_kernel<2><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
case 1: smooth_normals_kernel<1><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing);
}
cudaSafeCall( cudaGetLastError() );
......
#include <ftl/render/splat_params.hpp>
#include "splatter_cuda.hpp"
#include <ftl/rgbd/camera.hpp>
#include <ftl/cuda_common.hpp>
#include <ftl/cuda/weighting.hpp>
#include <ftl/cuda/makers.hpp>
#define T_PER_BLOCK 8
#define ACCUM_DIAMETER 8
using ftl::cuda::TextureObject;
using ftl::render::SplatParams;
using ftl::rgbd::Camera;
/*template <typename T>
__device__ inline T generateInput(const T &in, const SplatParams &params, const float4 &worldPos) {
return in;
}
template <>
__device__ inline uchar4 generateInput(const uchar4 &in, const SplatParams &params, const float4 &worldPos) {
return (params.m_flags & ftl::render::kShowDisconMask && worldPos.w < 0.0f) ?
make_uchar4(0,0,255,255) : // Show discontinuity mask in red
in;
}*/
template <typename A, typename B>
__device__ inline B weightInput(const A &in, float weight) {
return in * weight;
}
template <>
__device__ inline float4 weightInput(const uchar4 &in, float weight) {
return make_float4(
(float)in.x * weight,
(float)in.y * weight,
(float)in.z * weight,
(float)in.w * weight);
}
template <typename T>
__device__ inline void accumulateOutput(TextureObject<T> &out, TextureObject<float> &contrib, const uint2 &pos, const T &in, float w) {
atomicAdd(&out(pos.x, pos.y), in);
atomicAdd(&contrib(pos.x, pos.y), w);
}
template <>
__device__ inline void accumulateOutput(TextureObject<float4> &out, TextureObject<float> &contrib, const uint2 &pos, const float4 &in, float w) {
atomicAdd((float*)&out(pos.x, pos.y), in.x);
atomicAdd(((float*)&out(pos.x, pos.y))+1, in.y);
atomicAdd(((float*)&out(pos.x, pos.y))+2, in.z);
atomicAdd(((float*)&out(pos.x, pos.y))+3, in.w);
atomicAdd(&contrib(pos.x, pos.y), w);
}
/*
* Pass 2: Accumulate attribute contributions if the points pass a visibility test.
*/
template <typename A, typename B>
__global__ void reprojection_kernel(
TextureObject<A> in, // Attribute input
TextureObject<float> depth_src,
TextureObject<int> depth_in, // Virtual depth map
TextureObject<float4> normals,
TextureObject<B> out, // Accumulated output
TextureObject<float> contrib,
SplatParams params,
Camera camera, float4x4 poseInv) {
const int x = (blockIdx.x*blockDim.x + threadIdx.x);
const int y = blockIdx.y*blockDim.y + threadIdx.y;
const float d = (float)depth_in.tex2D((int)x, (int)y) / 100000.0f;
if (d < params.camera.minDepth || d > params.camera.maxDepth) return;
const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d);
//if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
const float3 camPos = poseInv * worldPos;
if (camPos.z < camera.minDepth) return;
if (camPos.z > camera.maxDepth) return;
const uint2 screenPos = camera.camToScreen<uint2>(camPos);
// Not on screen so stop now...
if (screenPos.x >= depth_src.width() || screenPos.y >= depth_src.height()) return;
// Calculate the dot product of surface normal and camera ray
const float3 n = poseInv.getFloat3x3() * make_float3(normals.tex2D((int)x, (int)y));
float3 ray = camera.screenToCam(screenPos.x, screenPos.y, 1.0f);
ray = ray / length(ray);
const float dotproduct = max(dot(ray,n),0.0f);
const float d2 = depth_src.tex2D((int)screenPos.x, (int)screenPos.y);
const A input = in.tex2D((int)screenPos.x, (int)screenPos.y); //generateInput(in.tex2D((int)screenPos.x, (int)screenPos.y), params, worldPos);
float weight = ftl::cuda::weighting(fabs(camPos.z - d2), 0.02f);
/* Buehler C. et al. 2001. Unstructured Lumigraph Rendering. */
/* Orts-Escolano S. et al. 2016. Holoportation: Virtual 3D teleportation in real-time. */
// This is the simple naive colour weighting. It might be good
// enough for our purposes if the alignment step prevents ghosting
// TODO: Use depth and perhaps the neighbourhood consistency in:
// Kuster C. et al. 2011. FreeCam: A hybrid camera system for interactive free-viewpoint video
if (params.m_flags & ftl::render::kNormalWeightColours) weight *= dotproduct;
const B weighted = make<B>(input) * weight; //weightInput(input, weight);
if (weight > 0.0f) {
accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
//out(screenPos.x, screenPos.y) = input;
}
}
template <typename A, typename B>
void ftl::cuda::reproject(
TextureObject<A> &in,
TextureObject<float> &depth_src, // Original 3D points
TextureObject<int> &depth_in, // Virtual depth map
TextureObject<float4> &normals,
TextureObject<B> &out, // Accumulated output
TextureObject<float> &contrib,
const SplatParams &params,
const Camera &camera, const float4x4 &poseInv, cudaStream_t stream) {
const dim3 gridSize((out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
reprojection_kernel<<<gridSize, blockSize, 0, stream>>>(
in,
depth_src,
depth_in,
normals,
out,
contrib,
params,
camera,
poseInv
);
cudaSafeCall( cudaGetLastError() );
}
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<uchar4> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &normals,
ftl::cuda::TextureObject<float4> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<float> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &normals,
ftl::cuda::TextureObject<float> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<float4> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &normals,
ftl::cuda::TextureObject<float4> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
//==============================================================================
// Without normals
//==============================================================================
/*
* Pass 2: Accumulate attribute contributions if the points pass a visibility test.
*/
template <typename A, typename B>
__global__ void reprojection_kernel(
TextureObject<A> in, // Attribute input
TextureObject<float> depth_src,
TextureObject<int> depth_in, // Virtual depth map
TextureObject<B> out, // Accumulated output
TextureObject<float> contrib,
SplatParams params,
Camera camera, float4x4 poseInv) {
const int x = (blockIdx.x*blockDim.x + threadIdx.x);
const int y = blockIdx.y*blockDim.y + threadIdx.y;
const float d = (float)depth_in.tex2D((int)x, (int)y) / 100000.0f;
if (d < params.camera.minDepth || d > params.camera.maxDepth) return;
const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d);
//if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
const float3 camPos = poseInv * worldPos;
if (camPos.z < camera.minDepth) return;
if (camPos.z > camera.maxDepth) return;
const uint2 screenPos = camera.camToScreen<uint2>(camPos);
// Not on screen so stop now...
if (screenPos.x >= depth_src.width() || screenPos.y >= depth_src.height()) return;
const float d2 = depth_src.tex2D((int)screenPos.x, (int)screenPos.y);
const A input = in.tex2D((int)screenPos.x, (int)screenPos.y); //generateInput(in.tex2D((int)screenPos.x, (int)screenPos.y), params, worldPos);
float weight = ftl::cuda::weighting(fabs(camPos.z - d2), 0.02f);
const B weighted = make<B>(input) * weight;
if (weight > 0.0f) {
accumulateOutput(out, contrib, make_uint2(x,y), weighted, weight);
//out(screenPos.x, screenPos.y) = input;
}
}
template <typename A, typename B>
void ftl::cuda::reproject(
TextureObject<A> &in,
TextureObject<float> &depth_src, // Original 3D points
TextureObject<int> &depth_in, // Virtual depth map
TextureObject<B> &out, // Accumulated output
TextureObject<float> &contrib,
const SplatParams &params,
const Camera &camera, const float4x4 &poseInv, cudaStream_t stream) {
const dim3 gridSize((out.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (out.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
reprojection_kernel<<<gridSize, blockSize, 0, stream>>>(
in,
depth_src,
depth_in,
out,
contrib,
params,
camera,
poseInv
);
cudaSafeCall( cudaGetLastError() );
}
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<uchar4> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<float> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template void ftl::cuda::reproject(
ftl::cuda::TextureObject<float4> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
#include <ftl/render/splat_params.hpp>
#include "splatter_cuda.hpp"
#include <ftl/rgbd/camera.hpp>
#include <ftl/cuda_common.hpp>
using ftl::rgbd::Camera;
using ftl::cuda::TextureObject;
using ftl::render::SplatParams;
#define T_PER_BLOCK 8
/*
* Convert source screen position to output screen coordinates.
*/
__global__ void screen_coord_kernel(TextureObject<float> depth,
TextureObject<float> depth_out,
TextureObject<short2> screen_out, SplatParams params, float4x4 pose, Camera camera) {
const int x = blockIdx.x*blockDim.x + threadIdx.x;
const int y = blockIdx.y*blockDim.y + threadIdx.y;
uint2 screenPos = make_uint2(30000,30000);
screen_out(x,y) = make_short2(screenPos.x, screenPos.y);
const float d = depth.tex2D(x, y);
const float3 worldPos = pose * camera.screenToCam(x,y,d);
if (d < camera.minDepth || d > camera.maxDepth) return;
// Find the virtual screen position of current point
const float3 camPos = params.m_viewMatrix * worldPos;
screenPos = params.camera.camToScreen<uint2>(camPos);
if (camPos.z < params.camera.minDepth || camPos.z > params.camera.maxDepth || screenPos.x >= params.camera.width || screenPos.y >= params.camera.height)
screenPos = make_uint2(30000,30000);
screen_out(x,y) = make_short2(screenPos.x, screenPos.y);
depth_out(x,y) = camPos.z;
}
void ftl::cuda::screen_coord(TextureObject<float> &depth, TextureObject<float> &depth_out, TextureObject<short2> &screen_out, const SplatParams &params, const float4x4 &pose, const Camera &camera, 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);
screen_coord_kernel<<<gridSize, blockSize, 0, stream>>>(depth, depth_out, screen_out, params, pose, camera);
cudaSafeCall( cudaGetLastError() );
}
......@@ -6,6 +6,7 @@
#include <ftl/cuda/weighting.hpp>
#include <ftl/cuda/intersections.hpp>
#include <ftl/cuda/warp.hpp>
#include <ftl/cuda/makers.hpp>
#define T_PER_BLOCK 8
#define UPSAMPLE_FACTOR 1.8f
......@@ -74,76 +75,53 @@ using ftl::cuda::warpSum;
}
}
void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<float4> &normals, TextureObject<int> &depth, SplatParams params, bool culling, 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);
if (culling) dibr_merge_kernel<true><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
else dibr_merge_kernel<false><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
cudaSafeCall( cudaGetLastError() );
}
//==============================================================================
__device__ inline float4 make_float4(const uchar4 &c) {
return make_float4(c.x,c.y,c.z,c.w);
}
__device__ inline float4 make_float4(const float4 &v) {
return v;
}
template <typename T>
__device__ inline T make();
template <>
__device__ inline uchar4 make() {
return make_uchar4(0,0,0,0);
}
/*
* Pass 1: Directly render each camera into virtual view but with no upsampling
* for sparse points.
*/
__global__ void dibr_merge_kernel(TextureObject<float4> points,
TextureObject<int> depth, SplatParams params) {
const int x = blockIdx.x*blockDim.x + threadIdx.x;
const int y = blockIdx.y*blockDim.y + threadIdx.y;
template <>
__device__ inline float4 make() {
return make_float4(0.0f,0.0f,0.0f,0.0f);
}
const float4 worldPos = points.tex2D(x, y);
if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
template <>
__device__ inline float make() {
return 0.0f;
}
// Find the virtual screen position of current point
const float3 camPos = params.m_viewMatrix * make_float3(worldPos);
if (camPos.z < params.camera.minDepth) return;
if (camPos.z > params.camera.maxDepth) return;
template <typename T>
__device__ inline T make(const float4 &);
const float d = camPos.z;
template <>
__device__ inline uchar4 make(const float4 &v) {
return make_uchar4((int)v.x, (int)v.y, (int)v.z, (int)v.w);
const uint2 screenPos = params.camera.camToScreen<uint2>(camPos);
const unsigned int cx = screenPos.x;
const unsigned int cy = screenPos.y;
if (d > params.camera.minDepth && d < params.camera.maxDepth && cx < depth.width() && cy < depth.height()) {
// Transform estimated point to virtual cam space and output z
atomicMin(&depth(cx,cy), d * 1000.0f);
}
}
template <>
__device__ inline float4 make(const float4 &v) {
return v;
}
void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<float4> &normals, TextureObject<int> &depth, SplatParams params, bool culling, 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);
template <>
__device__ inline float make(const float4 &v) {
return v.x;
if (culling) dibr_merge_kernel<true><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
else dibr_merge_kernel<false><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
cudaSafeCall( cudaGetLastError() );
}
template <typename T>
__device__ inline T make(const uchar4 &v);
void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<int> &depth, SplatParams params, 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);
template <>
__device__ inline float4 make(const uchar4 &v) {
return make_float4((float)v.x, (float)v.y, (float)v.z, (float)v.w);
dibr_merge_kernel<<<gridSize, blockSize, 0, stream>>>(points, depth, params);
cudaSafeCall( cudaGetLastError() );
}
template <typename T>
__device__ inline T make(float v);
//==============================================================================
template <>
__device__ inline float make(float v) {
return v;
}
/*
* Pass 1b: Expand splats to full size and merge
......
......@@ -6,6 +6,29 @@
namespace ftl {
namespace cuda {
void screen_coord(
ftl::cuda::TextureObject<float> &depth,
ftl::cuda::TextureObject<float> &depth_out,
ftl::cuda::TextureObject<short2> &screen_out,
const ftl::render::SplatParams &params,
const float4x4 &pose,
const ftl::rgbd::Camera &camera,
cudaStream_t stream);
void triangle_render1(
ftl::cuda::TextureObject<float> &depth_in,
ftl::cuda::TextureObject<int> &depth_out,
ftl::cuda::TextureObject<short2> &screen,
const ftl::render::SplatParams &params,
cudaStream_t stream);
void mesh_blender(
ftl::cuda::TextureObject<int> &depth_in,
ftl::cuda::TextureObject<int> &depth_out,
const ftl::rgbd::Camera &camera,
float alpha,
cudaStream_t stream);
void dibr_merge(
ftl::cuda::TextureObject<float4> &points,
ftl::cuda::TextureObject<float4> &normals,
......@@ -14,6 +37,12 @@ namespace cuda {
bool culling,
cudaStream_t stream);
void dibr_merge(
ftl::cuda::TextureObject<float4> &points,
ftl::cuda::TextureObject<int> &depth,
ftl::render::SplatParams params,
cudaStream_t stream);
template <typename T>
void splat(
ftl::cuda::TextureObject<float4> &normals,
......@@ -33,6 +62,29 @@ namespace cuda {
ftl::cuda::TextureObject<float> &contrib,
ftl::render::SplatParams &params, cudaStream_t stream);
template <typename A, typename B>
void reproject(
ftl::cuda::TextureObject<A> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<float4> &normals,
ftl::cuda::TextureObject<B> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template <typename A, typename B>
void reproject(
ftl::cuda::TextureObject<A> &in, // Original colour image
ftl::cuda::TextureObject<float> &depth_src, // Original 3D points
ftl::cuda::TextureObject<int> &depth_in, // Virtual depth map
ftl::cuda::TextureObject<B> &out, // Accumulated output
ftl::cuda::TextureObject<float> &contrib,
const ftl::render::SplatParams &params,
const ftl::rgbd::Camera &camera,
const float4x4 &poseInv, cudaStream_t stream);
template <typename A, typename B>
void dibr_normalise(
ftl::cuda::TextureObject<A> &in,
......
This diff is collapsed.
#include <ftl/render/splat_params.hpp>
#include "splatter_cuda.hpp"
#include <ftl/rgbd/camera.hpp>
#include <ftl/cuda_common.hpp>
#include <ftl/cuda/weighting.hpp>
using ftl::rgbd::Camera;
using ftl::cuda::TextureObject;
using ftl::render::SplatParams;
#define T_PER_BLOCK 8
__device__ inline float length2(int dx, int dy) { return dx*dx + dy*dy; }
__device__ inline float cross(const float2 &a, const float2 &b) {
return a.x*b.y - a.y*b.x;
}
__device__ inline bool within(float x) {
return 0.0f <= x <= 1.0f;
}
__device__ inline bool operator==(const float2 &a, const float2 &b) {
return a.x == b.x && a.y == b.y;
}
__device__ inline bool insideTriangle(const float2 &a, const float2 &b, const float2 &c, const float2 &p)
{
float det = (b.y - c.y)*(a.x - c.x) + (c.x - b.x)*(a.y - c.y);
float factor_alpha = (b.y - c.y)*(p.x - c.x) + (c.x - b.x)*(p.y - c.y);
float factor_beta = (c.y - a.y)*(p.x - c.x) + (a.x - c.x)*(p.y - c.y);
float alpha = factor_alpha / det;
float beta = factor_beta / det;
float gamma = 1.0 - alpha - beta;
return p == a || p == b || p == c || (within(alpha) && within(beta) && within(gamma));
}
__device__ inline void swap(short2 &a, short2 &b) {
short2 t = a;
a = b;
b = t;
}
__device__ void drawLine(TextureObject<int> &depth_out, int y, int x1, int x2, float d) {
for (int x=x1; x<=x2; ++x) {
if (x < 0) continue;
if (x >= depth_out.width()) return;
atomicMin(&depth_out(x,y), int(d*1000.0f));
}
}
/* See: https://github.com/bcrusco/CUDA-Rasterizer */
/**
* Calculate the signed area of a given triangle.
*/
__device__ static inline
float calculateSignedArea(const short2 &a, const short2 &b, const short2 &c) {
return 0.5f * (float(c.x - a.x) * float(b.y - a.y) - float(b.x - a.x) * float(c.y - a.y));
}
/**
* Helper function for calculating barycentric coordinates.
*/
__device__ static inline
float calculateBarycentricCoordinateValue(const short2 &a, const short2 &b, const short2 &c, const short2 (&tri)[3]) {
return calculateSignedArea(a,b,c) / calculateSignedArea(tri[0], tri[1], tri[2]);
}
/**
* Calculate barycentric coordinates.
* TODO: Update to handle triangles coming in and not the array
*/
__device__ static
float3 calculateBarycentricCoordinate(const short2 (&tri)[3], const short2 &point) {
float beta = calculateBarycentricCoordinateValue(tri[0], point, tri[2], tri);
float gamma = calculateBarycentricCoordinateValue(tri[0], tri[1], point, tri);
float alpha = 1.0 - beta - gamma;
return make_float3(alpha, beta, gamma);
}
/**
* Check if a barycentric coordinate is within the boundaries of a triangle.
*/
__host__ __device__ static
bool isBarycentricCoordInBounds(const float3 &barycentricCoord) {
return barycentricCoord.x >= 0.0 && barycentricCoord.x <= 1.0 &&
barycentricCoord.y >= 0.0 && barycentricCoord.y <= 1.0 &&
barycentricCoord.z >= 0.0 && barycentricCoord.z <= 1.0;
}
/**
* For a given barycentric coordinate, compute the corresponding z position
* (i.e. depth) on the triangle.
*/
__device__ static
float getZAtCoordinate(const float3 &barycentricCoord, const float (&tri)[3]) {
return (barycentricCoord.x * tri[0]
+ barycentricCoord.y * tri[1]
+ barycentricCoord.z * tri[2]);
}
/*
* Convert source screen position to output screen coordinates.
*/
template <int A, int B>
__global__ void triangle_render_1_kernel(
TextureObject<float> depth_in,
TextureObject<int> depth_out,
TextureObject<short2> screen, SplatParams params) {
const int x = blockIdx.x*blockDim.x + threadIdx.x;
const int y = blockIdx.y*blockDim.y + threadIdx.y;
if (x < 1 || x >= depth_in.width()-1 || y < 1 || y >= depth_in.height()-1) return;
float d[3];
d[0] = depth_in.tex2D(x,y);
d[1] = depth_in.tex2D(x+A,y);
d[2] = depth_in.tex2D(x,y+B);
// Is this triangle valid
if (fabs(d[0] - d[1]) > 0.04f || fabs(d[0] - d[2]) > 0.04f) return;
if (d[0] < params.camera.minDepth || d[0] > params.camera.maxDepth) return;
short2 v[3];
v[0] = screen.tex2D(x,y);
v[1] = screen.tex2D(x+A,y);
v[2] = screen.tex2D(x,y+B);
// Attempt to back face cull, but not great
//if ((v[1].x - v[0].x) * A < 0 || (v[2].y - v[0].y) * B < 0) return;
const int minX = min(v[0].x, min(v[1].x, v[2].x));
const int minY = min(v[0].y, min(v[1].y, v[2].y));
const int maxX = max(v[0].x, max(v[1].x, v[2].x));
const int maxY = max(v[0].y, max(v[1].y, v[2].y));
// Remove really large triangles
if ((maxX - minX) * (maxY - minY) > 200) return;
for (int sy=minY; sy <= maxY; ++sy) {
for (int sx=minX; sx <= maxX; ++sx) {
if (sx >= params.camera.width || sx < 0 || sy >= params.camera.height || sy < 0) continue;
float3 baryCentricCoordinate = calculateBarycentricCoordinate(v, make_short2(sx, sy));
if (isBarycentricCoordInBounds(baryCentricCoordinate)) {
float new_depth = getZAtCoordinate(baryCentricCoordinate, d);
atomicMin(&depth_out(sx,sy), int(new_depth*100000.0f));
}
}
}
}
void ftl::cuda::triangle_render1(TextureObject<float> &depth_in, TextureObject<int> &depth_out, TextureObject<short2> &screen, const SplatParams &params, 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);
triangle_render_1_kernel<1,1><<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, screen, params);
triangle_render_1_kernel<1,-1><<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, screen, params);
triangle_render_1_kernel<-1,1><<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, screen, params);
triangle_render_1_kernel<-1,-1><<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, screen, params);
cudaSafeCall( cudaGetLastError() );
}
// ==== BLENDER ========
/*
* Merge two depth maps together
*/
__global__ void mesh_blender_kernel(
TextureObject<int> depth_in,
TextureObject<int> depth_out,
ftl::rgbd::Camera camera,
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;
int a = depth_in.tex2D(x,y);
int b = depth_out.tex2D(x,y);
float mindepth = (float)min(a,b) / 100000.0f;
float maxdepth = (float)max(a,b) / 100000.0f;
float weight = ftl::cuda::weighting(maxdepth-mindepth, alpha);
//depth_out(x,y) = (int)(((float)mindepth + (float)maxdepth*weight) / (1.0f + weight) * 100000.0f);
float depth = (mindepth + maxdepth*weight) / (1.0f + weight);
depth_out(x,y) = (int)(depth * 100000.0f);
}
void ftl::cuda::mesh_blender(TextureObject<int> &depth_in, TextureObject<int> &depth_out, const ftl::rgbd::Camera &camera, 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);
mesh_blender_kernel<<<gridSize, blockSize, 0, stream>>>(depth_in, depth_out, camera, alpha);
cudaSafeCall( cudaGetLastError() );
}
......@@ -6,6 +6,10 @@
#include <cuda_runtime.h>
#include <ftl/cuda_util.hpp>
#ifndef __CUDACC__
#include <msgpack.hpp>
#endif
namespace ftl{
namespace rgbd {
......@@ -34,6 +38,10 @@ struct __align__(16) Camera {
* Convert screen plus depth into camera coordinates.
*/
__device__ float3 screenToCam(uint ux, uint uy, float depth) const;
#ifndef __CUDACC__
MSGPACK_DEFINE(fx,fy,cx,cy,width,height,minDepth,maxDepth,baseline,doffs);
#endif
};
};
......
......@@ -14,8 +14,7 @@ namespace detail {
* Also maintains statistics about the frame transmission for later analysis.
*/
struct NetFrame {
cv::Mat channel1;
cv::Mat channel2;
cv::cuda::GpuMat channel[2];
volatile int64_t timestamp;
std::atomic<int> chunk_count[2];
std::atomic<int> channel_count;
......
......@@ -62,8 +62,8 @@ class Source {
capability_t capabilities_;
ftl::rgbd::Source *host_;
ftl::rgbd::Camera params_;
cv::Mat rgb_;
cv::Mat depth_;
cv::cuda::GpuMat rgb_;
cv::cuda::GpuMat depth_;
int64_t timestamp_;
//Eigen::Matrix4f pose_;
};
......