Skip to content
Snippets Groups Projects
Commit a5d7d9af authored by Nicolas Pope's avatar Nicolas Pope
Browse files

Merge branch 'feature/216/triangles' into 'master'

Implements #216 triangle renderer

Closes #216

See merge request nicolas.pope/ftl!151
parents dab1353e 794dff6e
No related branches found
No related tags found
1 merge request!151Implements #216 triangle renderer
Pipeline #16018 passed
Showing
with 1268 additions and 78 deletions
...@@ -13,7 +13,7 @@ int main(int argc, char **argv) { ...@@ -13,7 +13,7 @@ int main(int argc, char **argv) {
ftl::net::Universe *net = ftl::create<ftl::net::Universe>(root, "net"); ftl::net::Universe *net = ftl::create<ftl::net::Universe>(root, "net");
net->start(); net->start();
//net->waitConnections(); net->waitConnections();
ftl::ctrl::Master *controller = new ftl::ctrl::Master(root, net); ftl::ctrl::Master *controller = new ftl::ctrl::Master(root, net);
controller->onLog([](const ftl::ctrl::LogEvent &e){ controller->onLog([](const ftl::ctrl::LogEvent &e){
......
...@@ -225,17 +225,23 @@ ftl::gui::Screen::Screen(ftl::Configurable *proot, ftl::net::Universe *pnet, ftl ...@@ -225,17 +225,23 @@ ftl::gui::Screen::Screen(ftl::Configurable *proot, ftl::net::Universe *pnet, ftl
popup->setLayout(new GroupLayout()); popup->setLayout(new GroupLayout());
popup->setTheme(toolbuttheme); popup->setTheme(toolbuttheme);
auto node_details = ctrl_->getSlaves(); //net_->onConnect([this,popup](ftl::net::Peer *p) {
std::vector<std::string> node_titles; {
LOG(INFO) << "NET CONNECT";
for (auto &d : node_details) { auto node_details = ctrl_->getSlaves();
auto peer = ftl::UUID(d["id"].get<std::string>()); std::vector<std::string> node_titles;
itembutton = new Button(popup, d["title"].get<std::string>());
itembutton->setCallback([this,popup,peer]() { for (auto &d : node_details) {
auto config_window = new ConfigWindow(this, ctrl_, peer); LOG(INFO) << "ADDING TITLE: " << d.dump();
config_window->setTheme(windowtheme); auto peer = ftl::UUID(d["id"].get<std::string>());
}); auto itembutton = new Button(popup, d["title"].get<std::string>());
itembutton->setCallback([this,popup,peer]() {
auto config_window = new ConfigWindow(this, ctrl_, peer);
config_window->setTheme(windowtheme);
});
}
} }
//});
itembutton = new Button(popup, "Local"); itembutton = new Button(popup, "Local");
itembutton->setCallback([this,popup]() { itembutton->setCallback([this,popup]() {
......
...@@ -19,7 +19,7 @@ ...@@ -19,7 +19,7 @@
#include <ftl/codecs/reader.hpp> #include <ftl/codecs/reader.hpp>
#include "ilw/ilw.hpp" #include "ilw/ilw.hpp"
#include <ftl/render/splat_render.hpp> #include <ftl/render/tri_render.hpp>
#include <fstream> #include <fstream>
#include <string> #include <string>
...@@ -99,8 +99,10 @@ static void run(ftl::Configurable *root) { ...@@ -99,8 +99,10 @@ static void run(ftl::Configurable *root) {
LOG(INFO) << "Found " << (max_stream+1) << " sources in " << path; LOG(INFO) << "Found " << (max_stream+1) << " sources in " << path;
int N = root->value("N", 100);
// For each stream found, add a source object // For each stream found, add a source object
for (int i=0; i<=max_stream; ++i) { for (int i=0; i<=min(max_stream,N-1); ++i) {
root->getConfig()["sources"].push_back(nlohmann::json{{"uri",std::string("file://") + path + std::string("#") + std::to_string(i)}}); root->getConfig()["sources"].push_back(nlohmann::json{{"uri",std::string("file://") + path + std::string("#") + std::to_string(i)}});
} }
} }
...@@ -168,7 +170,7 @@ static void run(ftl::Configurable *root) { ...@@ -168,7 +170,7 @@ static void run(ftl::Configurable *root) {
//ftl::voxhash::SceneRep *scene = ftl::create<ftl::voxhash::SceneRep>(root, "voxelhash"); //ftl::voxhash::SceneRep *scene = ftl::create<ftl::voxhash::SceneRep>(root, "voxelhash");
ftl::rgbd::Streamer *stream = ftl::create<ftl::rgbd::Streamer>(root, "stream", net); ftl::rgbd::Streamer *stream = ftl::create<ftl::rgbd::Streamer>(root, "stream", net);
ftl::rgbd::VirtualSource *virt = ftl::create<ftl::rgbd::VirtualSource>(root, "virtual"); ftl::rgbd::VirtualSource *virt = ftl::create<ftl::rgbd::VirtualSource>(root, "virtual");
ftl::render::Splatter *splat = ftl::create<ftl::render::Splatter>(root, "renderer", &scene_B); ftl::render::Triangular *splat = ftl::create<ftl::render::Triangular>(root, "renderer", &scene_B);
ftl::rgbd::Group *group = new ftl::rgbd::Group; ftl::rgbd::Group *group = new ftl::rgbd::Group;
ftl::ILW *align = ftl::create<ftl::ILW>(root, "merge"); ftl::ILW *align = ftl::create<ftl::ILW>(root, "merge");
......
...@@ -17,6 +17,7 @@ enum struct Channel : int { ...@@ -17,6 +17,7 @@ enum struct Channel : int {
Disparity = 3, Disparity = 3,
Depth2 = 3, Depth2 = 3,
Deviation = 4, Deviation = 4,
Screen = 4,
Normals = 5, // 32FC4 Normals = 5, // 32FC4
Points = 6, // 32FC4 Points = 6, // 32FC4
Confidence = 7, // 32F Confidence = 7, // 32F
......
...@@ -86,6 +86,7 @@ vector<string> Master::getConfigurables() { ...@@ -86,6 +86,7 @@ vector<string> Master::getConfigurables() {
vector<string> Master::getConfigurables(const ftl::UUID &peer) { vector<string> Master::getConfigurables(const ftl::UUID &peer) {
try { try {
LOG(INFO) << "LISTING CONFIGS";
return net_->call<vector<string>>(peer, "list_configurables"); return net_->call<vector<string>>(peer, "list_configurables");
} catch (...) { } catch (...) {
return {}; return {};
......
add_library(ftlrender add_library(ftlrender
src/splat_render.cpp src/splatter.cpp
src/splatter.cu src/splatter.cu
src/points.cu src/points.cu
src/normals.cu src/normals.cu
src/mask.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 # 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_
...@@ -226,7 +226,9 @@ void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output, ...@@ -226,7 +226,9 @@ void ftl::cuda::normals(ftl::cuda::TextureObject<float4> &output,
switch (radius) { switch (radius) {
case 7: smooth_normals_kernel<7><<<gridSize, blockSize, 0, stream>>>(temp, output, input, camera, pose, smoothing); 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 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() ); 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) / 1000.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) / 1000.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 @@ ...@@ -6,6 +6,7 @@
#include <ftl/cuda/weighting.hpp> #include <ftl/cuda/weighting.hpp>
#include <ftl/cuda/intersections.hpp> #include <ftl/cuda/intersections.hpp>
#include <ftl/cuda/warp.hpp> #include <ftl/cuda/warp.hpp>
#include <ftl/cuda/makers.hpp>
#define T_PER_BLOCK 8 #define T_PER_BLOCK 8
#define UPSAMPLE_FACTOR 1.8f #define UPSAMPLE_FACTOR 1.8f
...@@ -74,76 +75,53 @@ using ftl::cuda::warpSum; ...@@ -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); * Pass 1: Directly render each camera into virtual view but with no upsampling
const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); * for sparse points.
*/
if (culling) dibr_merge_kernel<true><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params); __global__ void dibr_merge_kernel(TextureObject<float4> points,
else dibr_merge_kernel<false><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params); TextureObject<int> depth, SplatParams params) {
cudaSafeCall( cudaGetLastError() ); const int x = blockIdx.x*blockDim.x + threadIdx.x;
} const int y = blockIdx.y*blockDim.y + threadIdx.y;
//==============================================================================
__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 <> const float4 worldPos = points.tex2D(x, y);
__device__ inline float4 make() { if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return;
return make_float4(0.0f,0.0f,0.0f,0.0f);
}
template <> // Find the virtual screen position of current point
__device__ inline float make() { const float3 camPos = params.m_viewMatrix * make_float3(worldPos);
return 0.0f; if (camPos.z < params.camera.minDepth) return;
} if (camPos.z > params.camera.maxDepth) return;
template <typename T> const float d = camPos.z;
__device__ inline T make(const float4 &);
template <> const uint2 screenPos = params.camera.camToScreen<uint2>(camPos);
__device__ inline uchar4 make(const float4 &v) { const unsigned int cx = screenPos.x;
return make_uchar4((int)v.x, (int)v.y, (int)v.z, (int)v.w); 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 <> void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<float4> &normals, TextureObject<int> &depth, SplatParams params, bool culling, cudaStream_t stream) {
__device__ inline float4 make(const float4 &v) { const dim3 gridSize((depth.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (depth.height() + T_PER_BLOCK - 1)/T_PER_BLOCK);
return v; const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK);
}
template <> if (culling) dibr_merge_kernel<true><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
__device__ inline float make(const float4 &v) { else dibr_merge_kernel<false><<<gridSize, blockSize, 0, stream>>>(points, normals, depth, params);
return v.x; cudaSafeCall( cudaGetLastError() );
} }
template <typename T> void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<int> &depth, SplatParams params, cudaStream_t stream) {
__device__ inline T make(const uchar4 &v); 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 <> dibr_merge_kernel<<<gridSize, blockSize, 0, stream>>>(points, depth, params);
__device__ inline float4 make(const uchar4 &v) { cudaSafeCall( cudaGetLastError() );
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;
}
/* /*
* Pass 1b: Expand splats to full size and merge * Pass 1b: Expand splats to full size and merge
......
...@@ -6,6 +6,22 @@ ...@@ -6,6 +6,22 @@
namespace ftl { namespace ftl {
namespace cuda { 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 dibr_merge( void dibr_merge(
ftl::cuda::TextureObject<float4> &points, ftl::cuda::TextureObject<float4> &points,
ftl::cuda::TextureObject<float4> &normals, ftl::cuda::TextureObject<float4> &normals,
...@@ -14,6 +30,12 @@ namespace cuda { ...@@ -14,6 +30,12 @@ namespace cuda {
bool culling, bool culling,
cudaStream_t stream); 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> template <typename T>
void splat( void splat(
ftl::cuda::TextureObject<float4> &normals, ftl::cuda::TextureObject<float4> &normals,
...@@ -33,6 +55,29 @@ namespace cuda { ...@@ -33,6 +55,29 @@ namespace cuda {
ftl::cuda::TextureObject<float> &contrib, ftl::cuda::TextureObject<float> &contrib,
ftl::render::SplatParams &params, cudaStream_t stream); 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> template <typename A, typename B>
void dibr_normalise( void dibr_normalise(
ftl::cuda::TextureObject<A> &in, ftl::cuda::TextureObject<A> &in,
......
#include <ftl/render/tri_render.hpp>
#include <ftl/utility/matrix_conversion.hpp>
#include "splatter_cuda.hpp"
#include <ftl/cuda/points.hpp>
#include <ftl/cuda/normals.hpp>
#include <ftl/cuda/mask.hpp>
#include <opencv2/core/cuda_stream_accessor.hpp>
#include <string>
using ftl::render::Triangular;
using ftl::codecs::Channel;
using ftl::codecs::Channels;
using ftl::rgbd::Format;
using cv::cuda::GpuMat;
using std::stoul;
using ftl::cuda::Mask;
static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) {
Eigen::Affine3d rx =
Eigen::Affine3d(Eigen::AngleAxisd(ax, Eigen::Vector3d(1, 0, 0)));
Eigen::Affine3d ry =
Eigen::Affine3d(Eigen::AngleAxisd(ay, Eigen::Vector3d(0, 1, 0)));
Eigen::Affine3d rz =
Eigen::Affine3d(Eigen::AngleAxisd(az, Eigen::Vector3d(0, 0, 1)));
return rz * rx * ry;
}
/*
* Parse a CSS style colour string into a scalar.
*/
static cv::Scalar parseCVColour(const std::string &colour) {
std::string c = colour;
if (c[0] == '#') {
c.erase(0, 1);
unsigned long value = stoul(c.c_str(), nullptr, 16);
return cv::Scalar(
(value >> 0) & 0xff,
(value >> 8) & 0xff,
(value >> 16) & 0xff,
(value >> 24) & 0xff
);
}
return cv::Scalar(0,0,0,0);
}
/*
* Parse a CSS style colour string into a scalar.
*/
static uchar4 parseCUDAColour(const std::string &colour) {
std::string c = colour;
if (c[0] == '#') {
c.erase(0, 1);
unsigned long value = stoul(c.c_str(), nullptr, 16);
return make_uchar4(
(value >> 0) & 0xff,
(value >> 8) & 0xff,
(value >> 16) & 0xff,
(value >> 24) & 0xff
);
}
return make_uchar4(0,0,0,0);
}
Triangular::Triangular(nlohmann::json &config, ftl::rgbd::FrameSet *fs) : ftl::render::Renderer(config), scene_(fs) {
if (config["clipping"].is_object()) {
auto &c = config["clipping"];
float rx = c.value("pitch", 0.0f);
float ry = c.value("yaw", 0.0f);
float rz = c.value("roll", 0.0f);
float x = c.value("x", 0.0f);
float y = c.value("y", 0.0f);
float z = c.value("z", 0.0f);
float width = c.value("width", 1.0f);
float height = c.value("height", 1.0f);
float depth = c.value("depth", 1.0f);
Eigen::Affine3f r = create_rotation_matrix(rx, ry, rz).cast<float>();
Eigen::Translation3f trans(Eigen::Vector3f(x,y,z));
Eigen::Affine3f t(trans);
clip_.origin = MatrixConversion::toCUDA(r.matrix() * t.matrix());
clip_.size = make_float3(width, height, depth);
clipping_ = value("clipping_enabled", true);
} else {
clipping_ = false;
}
on("clipping_enabled", [this](const ftl::config::Event &e) {
clipping_ = value("clipping_enabled", true);
});
norm_filter_ = value("normal_filter", -1.0f);
on("normal_filter", [this](const ftl::config::Event &e) {
norm_filter_ = value("normal_filter", -1.0f);
});
backcull_ = value("back_cull", true);
on("back_cull", [this](const ftl::config::Event &e) {
backcull_ = value("back_cull", true);
});
mesh_ = value("meshing", true);
on("meshing", [this](const ftl::config::Event &e) {
mesh_ = value("meshing", true);
});
background_ = parseCVColour(value("background", std::string("#4c4c4c")));
on("background", [this](const ftl::config::Event &e) {
background_ = parseCVColour(value("background", std::string("#4c4c4c")));
});
light_diffuse_ = parseCUDAColour(value("diffuse", std::string("#e0e0e0")));
on("diffuse", [this](const ftl::config::Event &e) {
light_diffuse_ = parseCUDAColour(value("diffuse", std::string("#e0e0e0")));
});
light_ambient_ = parseCUDAColour(value("ambient", std::string("#0e0e0e")));
on("ambient", [this](const ftl::config::Event &e) {
light_ambient_ = parseCUDAColour(value("ambient", std::string("#0e0e0e")));
});
light_pos_ = make_float3(value("light_x", 0.3f), value("light_y", 0.2f), value("light_z", 1.0f));
on("light_x", [this](const ftl::config::Event &e) { light_pos_.x = value("light_x", 0.3f); });
on("light_y", [this](const ftl::config::Event &e) { light_pos_.y = value("light_y", 0.3f); });
on("light_z", [this](const ftl::config::Event &e) { light_pos_.z = value("light_z", 0.3f); });
cudaSafeCall(cudaStreamCreate(&stream_));
}
Triangular::~Triangular() {
}
template <typename T>
struct AccumSelector {
typedef float4 type;
static constexpr Channel channel = Channel::Colour;
//static constexpr cv::Scalar value = cv::Scalar(0.0f,0.0f,0.0f,0.0f);
};
template <>
struct AccumSelector<float> {
typedef float type;
static constexpr Channel channel = Channel::Colour2;
//static constexpr cv::Scalar value = cv::Scalar(0.0f);
};
/*template <typename T>
void Triangular::__blendChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t stream) {
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
temp_.create<GpuMat>(
AccumSelector<T>::channel,
Format<typename AccumSelector<T>::type>(params_.camera.width, params_.camera.height)
).setTo(cv::Scalar(0.0f), cvstream);
temp_.get<GpuMat>(Channel::Contribution).setTo(cv::Scalar(0.0f), cvstream);
temp_.createTexture<float>(Channel::Contribution);
for (auto &f : scene_->frames) {
if (f.get<GpuMat>(in).type() == CV_8UC3) {
// Convert to 4 channel colour
auto &col = f.get<GpuMat>(in);
GpuMat tmp(col.size(), CV_8UC4);
cv::cuda::swap(col, tmp);
cv::cuda::cvtColor(tmp,col, cv::COLOR_BGR2BGRA);
}
ftl::cuda::dibr_attribute(
f.createTexture<T>(in),
f.createTexture<float4>(Channel::Points),
temp_.getTexture<int>(Channel::Depth2),
temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
temp_.getTexture<float>(Channel::Contribution),
params_, stream
);
}
ftl::cuda::dibr_normalise(
temp_.getTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
output.createTexture<T>(out),
temp_.getTexture<float>(Channel::Contribution),
stream
);
}*/
template <typename T>
void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t stream) {
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
temp_.create<GpuMat>(
AccumSelector<T>::channel,
Format<typename AccumSelector<T>::type>(params_.camera.width, params_.camera.height)
).setTo(cv::Scalar(0.0f), cvstream);
temp_.get<GpuMat>(Channel::Contribution).setTo(cv::Scalar(0.0f), cvstream);
temp_.createTexture<float>(Channel::Contribution);
for (size_t i=0; i < scene_->frames.size(); ++i) {
auto &f = scene_->frames[i];
auto *s = scene_->sources[i];
if (f.get<GpuMat>(in).type() == CV_8UC3) {
// Convert to 4 channel colour
auto &col = f.get<GpuMat>(in);
GpuMat tmp(col.size(), CV_8UC4);
cv::cuda::swap(col, tmp);
cv::cuda::cvtColor(tmp,col, cv::COLOR_BGR2BGRA);
}
auto poseInv = MatrixConversion::toCUDA(s->getPose().cast<float>().inverse());
if (mesh_) {
ftl::cuda::reproject(
f.createTexture<T>(in),
f.createTexture<float>(Channel::Depth), // TODO: Use depth?
temp_.getTexture<int>(Channel::Depth2),
accum_.getTexture<float4>(Channel::Normals),
temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
temp_.getTexture<float>(Channel::Contribution),
params_,
s->parameters(),
poseInv, stream
);
} else {
// Can't use normals with point cloud version
ftl::cuda::reproject(
f.createTexture<T>(in),
f.createTexture<float>(Channel::Depth), // TODO: Use depth?
temp_.getTexture<int>(Channel::Depth2),
temp_.createTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
temp_.getTexture<float>(Channel::Contribution),
params_,
s->parameters(),
poseInv, stream
);
}
}
ftl::cuda::dibr_normalise(
temp_.getTexture<typename AccumSelector<T>::type>(AccumSelector<T>::channel),
output.createTexture<T>(out),
temp_.getTexture<float>(Channel::Contribution),
stream
);
}
/*void Triangular::_blendChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t stream) {
int type = output.get<GpuMat>(out).type(); // == CV_32F; //ftl::rgbd::isFloatChannel(channel);
switch (type) {
case CV_32F : __blendChannel<float>(output, in, out, stream); break;
case CV_32FC4 : __blendChannel<float4>(output, in, out, stream); break;
case CV_8UC4 : __blendChannel<uchar4>(output, in, out, stream); break;
default : LOG(ERROR) << "Invalid output channel format";
}
}*/
void Triangular::_reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t stream) {
int type = output.get<GpuMat>(out).type(); // == CV_32F; //ftl::rgbd::isFloatChannel(channel);
switch (type) {
case CV_32F : __reprojectChannel<float>(output, in, out, stream); break;
case CV_32FC4 : __reprojectChannel<float4>(output, in, out, stream); break;
case CV_8UC4 : __reprojectChannel<uchar4>(output, in, out, stream); break;
default : LOG(ERROR) << "Invalid output channel format";
}
}
void Triangular::_dibr(cudaStream_t stream) {
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
temp_.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0x7FFFFFFF), cvstream);
for (size_t i=0; i < scene_->frames.size(); ++i) {
auto &f = scene_->frames[i];
auto *s = scene_->sources[i];
if (f.empty(Channel::Depth + Channel::Colour)) {
LOG(ERROR) << "Missing required channel";
continue;
}
ftl::cuda::dibr_merge(
f.createTexture<float4>(Channel::Points),
temp_.createTexture<int>(Channel::Depth2),
params_, stream
);
}
}
void Triangular::_mesh(cudaStream_t stream) {
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
temp_.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0x7FFFFFFF), cvstream);
for (size_t i=0; i < scene_->frames.size(); ++i) {
auto &f = scene_->frames[i];
auto *s = scene_->sources[i];
if (f.empty(Channel::Depth + Channel::Colour)) {
LOG(ERROR) << "Missing required channel";
continue;
}
auto pose = MatrixConversion::toCUDA(s->getPose().cast<float>());
ftl::cuda::screen_coord(
f.createTexture<float>(Channel::Depth),
f.createTexture<float>(Channel::Depth2, Format<float>(f.get<GpuMat>(Channel::Depth).size())),
f.createTexture<short2>(Channel::Screen, Format<short2>(f.get<GpuMat>(Channel::Depth).size())),
params_, pose, s->parameters(), stream
);
ftl::cuda::triangle_render1(
f.getTexture<float>(Channel::Depth2),
temp_.createTexture<int>(Channel::Depth2),
f.getTexture<short2>(Channel::Screen),
params_, stream
);
//LOG(INFO) << "DIBR DONE";
}
}
void Triangular::_renderChannel(
ftl::rgbd::Frame &out,
Channel channel_in, Channel channel_out, cudaStream_t stream)
{
if (channel_out == Channel::None || channel_in == Channel::None) return;
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream);
if (scene_->frames.size() < 1) return;
bool is_float = out.get<GpuMat>(channel_out).type() == CV_32F; //ftl::rgbd::isFloatChannel(channel);
bool is_4chan = out.get<GpuMat>(channel_out).type() == CV_32FC4;
temp_.createTexture<float4>(Channel::Colour);
temp_.createTexture<float>(Channel::Contribution);
// FIXME: Using colour 2 in this way seems broken since it is already used
if (is_4chan) {
accum_.create<GpuMat>(channel_out, Format<float4>(params_.camera.width, params_.camera.height));
accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0.0f,0.0f,0.0f,0.0f), cvstream);
} else if (is_float) {
accum_.create<GpuMat>(channel_out, Format<float>(params_.camera.width, params_.camera.height));
accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0.0f), cvstream);
} else {
accum_.create<GpuMat>(channel_out, Format<uchar4>(params_.camera.width, params_.camera.height));
accum_.get<GpuMat>(channel_out).setTo(cv::Scalar(0,0,0,0), cvstream);
}
_reprojectChannel(out, channel_in, channel_out, stream);
}
bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) {
SHARED_LOCK(scene_->mtx, lk);
if (!src->isReady()) return false;
scene_->upload(Channel::Colour + Channel::Depth, stream_);
const auto &camera = src->parameters();
//cudaSafeCall(cudaSetDevice(scene_->getCUDADevice()));
// Create all the required channels
out.create<GpuMat>(Channel::Depth, Format<float>(camera.width, camera.height));
out.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height));
if (scene_->frames.size() == 0) return false;
auto &g = scene_->frames[0].get<GpuMat>(Channel::Colour);
temp_.create<GpuMat>(Channel::Colour, Format<float4>(camera.width, camera.height));
temp_.create<GpuMat>(Channel::Contribution, Format<float>(camera.width, camera.height));
temp_.create<GpuMat>(Channel::Depth, Format<int>(camera.width, camera.height));
temp_.create<GpuMat>(Channel::Depth2, Format<int>(camera.width, camera.height));
temp_.create<GpuMat>(Channel::Normals, Format<float4>(camera.width, camera.height)); //g.cols, g.rows));
cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream_);
// Parameters object to pass to CUDA describing the camera
SplatParams &params = params_;
params.m_flags = 0;
//if () params.m_flags |= ftl::render::kShowDisconMask;
if (value("normal_weight_colours", true)) params.m_flags |= ftl::render::kNormalWeightColours;
params.m_viewMatrix = MatrixConversion::toCUDA(src->getPose().cast<float>().inverse());
params.m_viewMatrixInverse = MatrixConversion::toCUDA(src->getPose().cast<float>());
params.camera = camera;
// Clear all channels to 0 or max depth
out.get<GpuMat>(Channel::Depth).setTo(cv::Scalar(1000.0f), cvstream);
out.get<GpuMat>(Channel::Colour).setTo(background_, cvstream);
//LOG(INFO) << "Render ready: " << camera.width << "," << camera.height;
bool show_discon = value("show_discontinuity_mask", false);
bool show_fill = value("show_filled", false);
temp_.createTexture<int>(Channel::Depth);
//temp_.get<GpuMat>(Channel::Normals).setTo(cv::Scalar(0.0f,0.0f,0.0f,0.0f), cvstream);
// Display mask values
for (int i=0; i<scene_->frames.size(); ++i) {
auto &f = scene_->frames[i];
auto s = scene_->sources[i];
if (f.hasChannel(Channel::Mask)) {
if (show_discon) {
ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<int>(Channel::Mask), Mask::kMask_Discontinuity, make_uchar4(0,0,255,255), stream_);
}
if (show_fill) {
ftl::cuda::show_mask(f.getTexture<uchar4>(Channel::Colour), f.getTexture<int>(Channel::Mask), Mask::kMask_Filled, make_uchar4(0,255,0,255), stream_);
}
}
/*// Needs to create points channel first?
if (!f.hasChannel(Channel::Points)) {
//LOG(INFO) << "Creating points... " << s->parameters().width;
auto &t = f.createTexture<float4>(Channel::Points, Format<float4>(f.get<GpuMat>(Channel::Colour).size()));
auto pose = MatrixConversion::toCUDA(s->getPose().cast<float>()); //.inverse());
ftl::cuda::point_cloud(t, f.createTexture<float>(Channel::Depth), s->parameters(), pose, 0, stream_);
//LOG(INFO) << "POINTS Added";
}
// Clip first?
if (clipping_) {
ftl::cuda::clipping(f.createTexture<float4>(Channel::Points), clip_, stream_);
}
if (!f.hasChannel(Channel::Normals)) {
Eigen::Matrix4f matrix = s->getPose().cast<float>().transpose();
auto pose = MatrixConversion::toCUDA(matrix);
auto &g = f.get<GpuMat>(Channel::Colour);
ftl::cuda::normals(f.createTexture<float4>(Channel::Normals, Format<float4>(g.cols, g.rows)),
temp_.getTexture<float4>(Channel::Normals),
f.getTexture<float4>(Channel::Points),
1, 0.02f,
s->parameters(), pose.getFloat3x3(), stream_);
if (norm_filter_ > -0.1f) {
ftl::cuda::normal_filter(f.getTexture<float4>(Channel::Normals), f.getTexture<float4>(Channel::Points), s->parameters(), pose, norm_filter_, stream_);
}
}*/
}
Channel chan = src->getChannel();
int aligned_source = value("aligned_source",-1);
if (aligned_source >= 0 && aligned_source < scene_->frames.size()) {
// FIXME: Output may not be same resolution as source!
cudaSafeCall(cudaStreamSynchronize(stream_));
scene_->frames[aligned_source].copyTo(Channel::Depth + Channel::Colour, out);
if (chan == Channel::Normals) {
// Convert normal to single float value
temp_.create<GpuMat>(Channel::Colour, Format<uchar4>(camera.width, camera.height)).setTo(cv::Scalar(0,0,0,0), cvstream);
ftl::cuda::normal_visualise(scene_->frames[aligned_source].getTexture<float4>(Channel::Normals), temp_.createTexture<uchar4>(Channel::Colour),
light_pos_,
light_diffuse_,
light_ambient_, stream_);
// Put in output as single float
cv::cuda::swap(temp_.get<GpuMat>(Channel::Colour), out.create<GpuMat>(Channel::Normals));
out.resetTexture(Channel::Normals);
}
return true;
}
// Create and render triangles for depth
if (mesh_) {
_mesh(stream_);
} else {
_dibr(stream_);
}
// Generate normals for final virtual image
ftl::cuda::normals(accum_.createTexture<float4>(Channel::Normals, Format<float4>(camera.width, camera.height)),
temp_.createTexture<float4>(Channel::Normals),
temp_.getTexture<int>(Channel::Depth2),
1, 0.02f,
params_.camera, params_.m_viewMatrix.getFloat3x3(), params_.m_viewMatrixInverse.getFloat3x3(), stream_);
// Reprojection of colours onto surface
_renderChannel(out, Channel::Colour, Channel::Colour, stream_);
if (chan == Channel::Depth)
{
// Just convert int depth to float depth
temp_.get<GpuMat>(Channel::Depth2).convertTo(out.get<GpuMat>(Channel::Depth), CV_32F, 1.0f / 1000.0f, cvstream);
} else if (chan == Channel::Normals) {
// Visualise normals to RGBA
out.create<GpuMat>(Channel::Normals, Format<uchar4>(camera.width, camera.height)).setTo(cv::Scalar(0,0,0,0), cvstream);
ftl::cuda::normal_visualise(accum_.getTexture<float4>(Channel::Normals), out.createTexture<uchar4>(Channel::Normals),
light_pos_,
light_diffuse_,
light_ambient_, stream_);
}
//else if (chan == Channel::Contribution)
//{
// cv::cuda::swap(temp_.get<GpuMat>(Channel::Contribution), out.create<GpuMat>(Channel::Contribution));
//}
else if (chan == Channel::Density) {
out.create<GpuMat>(chan, Format<float>(camera.width, camera.height));
out.get<GpuMat>(chan).setTo(cv::Scalar(0.0f), cvstream);
_renderChannel(out, Channel::Depth, Channel::Density, stream_);
}
else if (chan == Channel::Right)
{
float baseline = camera.baseline;
//Eigen::Translation3f translation(baseline, 0.0f, 0.0f);
//Eigen::Affine3f transform(translation);
//Eigen::Matrix4f matrix = transform.matrix() * src->getPose().cast<float>();
Eigen::Matrix4f transform = Eigen::Matrix4f::Identity();
transform(0, 3) = baseline;
Eigen::Matrix4f matrix = transform.inverse() * src->getPose().cast<float>();
params.m_viewMatrix = MatrixConversion::toCUDA(matrix.inverse());
params.m_viewMatrixInverse = MatrixConversion::toCUDA(matrix);
params.camera = src->parameters(Channel::Right);
out.create<GpuMat>(Channel::Right, Format<uchar4>(camera.width, camera.height));
out.get<GpuMat>(Channel::Right).setTo(background_, cvstream);
_dibr(stream_); // Need to re-dibr due to pose change
_renderChannel(out, Channel::Left, Channel::Right, stream_);
} else if (chan != Channel::None) {
if (ftl::codecs::isFloatChannel(chan)) {
out.create<GpuMat>(chan, Format<float>(camera.width, camera.height));
out.get<GpuMat>(chan).setTo(cv::Scalar(0.0f), cvstream);
} else {
out.create<GpuMat>(chan, Format<uchar4>(camera.width, camera.height));
out.get<GpuMat>(chan).setTo(background_, cvstream);
}
_renderChannel(out, chan, chan, stream_);
}
cudaSafeCall(cudaStreamSynchronize(stream_));
return true;
}
#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
__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*1000.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() );
}
...@@ -112,7 +112,7 @@ template<> cv::Mat& Frame::get(ftl::codecs::Channel channel) { ...@@ -112,7 +112,7 @@ template<> cv::Mat& Frame::get(ftl::codecs::Channel channel) {
// Add channel if not already there // Add channel if not already there
if (!channels_.has(channel)) { if (!channels_.has(channel)) {
throw ftl::exception("Frame channel does not exist"); throw ftl::exception(ftl::Formatter() << "Frame channel does not exist: " << (int)channel);
} }
return _get(channel).host; return _get(channel).host;
...@@ -132,7 +132,7 @@ template<> cv::cuda::GpuMat& Frame::get(ftl::codecs::Channel channel) { ...@@ -132,7 +132,7 @@ template<> cv::cuda::GpuMat& Frame::get(ftl::codecs::Channel channel) {
// Add channel if not already there // Add channel if not already there
if (!channels_.has(channel)) { if (!channels_.has(channel)) {
throw ftl::exception("Frame channel does not exist"); throw ftl::exception(ftl::Formatter() << "Frame channel does not exist: " << (int)channel);
} }
return _get(channel).gpu; return _get(channel).gpu;
...@@ -147,7 +147,7 @@ template<> const cv::Mat& Frame::get(ftl::codecs::Channel channel) const { ...@@ -147,7 +147,7 @@ template<> const cv::Mat& Frame::get(ftl::codecs::Channel channel) const {
LOG(FATAL) << "Getting GPU channel on CPU without explicit 'download'"; LOG(FATAL) << "Getting GPU channel on CPU without explicit 'download'";
} }
if (!channels_.has(channel)) throw ftl::exception("Frame channel does not exist"); if (!channels_.has(channel)) throw ftl::exception(ftl::Formatter() << "Frame channel does not exist: " << (int)channel);
return _get(channel).host; return _get(channel).host;
} }
...@@ -163,7 +163,7 @@ template<> const cv::cuda::GpuMat& Frame::get(ftl::codecs::Channel channel) cons ...@@ -163,7 +163,7 @@ template<> const cv::cuda::GpuMat& Frame::get(ftl::codecs::Channel channel) cons
// Add channel if not already there // Add channel if not already there
if (!channels_.has(channel)) { if (!channels_.has(channel)) {
throw ftl::exception("Frame channel does not exist"); throw ftl::exception(ftl::Formatter() << "Frame channel does not exist: " << (int)channel);
} }
return _get(channel).gpu; return _get(channel).gpu;
......
...@@ -229,7 +229,7 @@ void NetSource::_processConfig(const ftl::codecs::Packet &pkt) { ...@@ -229,7 +229,7 @@ void NetSource::_processConfig(const ftl::codecs::Packet &pkt) {
auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size());
unpacked.get().convert(cfg); unpacked.get().convert(cfg);
LOG(INFO) << "Config Received: " << std::get<1>(cfg); //LOG(INFO) << "Config Received: " << std::get<1>(cfg);
// TODO: This needs to be put in safer / better location // TODO: This needs to be put in safer / better location
host_->set(std::get<0>(cfg), nlohmann::json::parse(std::get<1>(cfg))); host_->set(std::get<0>(cfg), nlohmann::json::parse(std::get<1>(cfg)));
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment