From 517987fdcd71b454a7a8b2b567fabc604005f560 Mon Sep 17 00:00:00 2001 From: Nicolas Pope <nwpope@utu.fi> Date: Sat, 2 Nov 2019 21:03:34 +0200 Subject: [PATCH] WIP Operator refactor --- CMakeLists.txt | 2 +- applications/reconstruct/CMakeLists.txt | 2 +- applications/reconstruct/src/main.cpp | 24 +++---- components/operators/CMakeLists.txt | 8 +-- .../include/ftl/operators/colours.hpp | 18 ++--- .../include/ftl/operators/operator.hpp | 62 ++++++++++------ .../include/ftl/operators/smoothing.hpp | 60 ++++++++++++---- components/operators/src/colours.cpp | 14 ++-- components/operators/src/operator.cpp | 51 +++++++++---- components/operators/src/smoothing.cpp | 71 ++++++++++--------- .../cpp/include/ftl/render/tri_render.hpp | 4 +- components/renderers/cpp/src/tri_render.cpp | 6 +- 12 files changed, 201 insertions(+), 121 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index af6a4173c..fb73e5cf9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -225,7 +225,7 @@ add_subdirectory(components/codecs) add_subdirectory(components/net) add_subdirectory(components/rgbd-sources) add_subdirectory(components/control/cpp) -add_subdirectory(components/filters) +add_subdirectory(components/operators) add_subdirectory(applications/calibration) add_subdirectory(applications/groupview) add_subdirectory(applications/player) diff --git a/applications/reconstruct/CMakeLists.txt b/applications/reconstruct/CMakeLists.txt index 1896417ea..b089d4a1a 100644 --- a/applications/reconstruct/CMakeLists.txt +++ b/applications/reconstruct/CMakeLists.txt @@ -36,6 +36,6 @@ set_property(TARGET ftl-reconstruct PROPERTY CUDA_SEPARABLE_COMPILATION ON) endif() #target_include_directories(cv-node PUBLIC ${PROJECT_SOURCE_DIR}/include) -target_link_libraries(ftl-reconstruct ftlcommon ftlrgbd Threads::Threads ${OpenCV_LIBS} ftlctrl ftlnet ftlrender ftlfilter) +target_link_libraries(ftl-reconstruct ftlcommon ftlrgbd Threads::Threads ${OpenCV_LIBS} ftlctrl ftlnet ftlrender ftloperators) diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp index 948d9a574..9b2eda9de 100644 --- a/applications/reconstruct/src/main.cpp +++ b/applications/reconstruct/src/main.cpp @@ -30,8 +30,8 @@ #include <opencv2/opencv.hpp> #include <ftl/net/universe.hpp> -#include <ftl/filters/smoothing.hpp> -#include <ftl/filters/colours.hpp> +#include <ftl/operators/smoothing.hpp> +#include <ftl/operators/colours.hpp> #include <ftl/cuda/normals.hpp> #include <ftl/registration.hpp> @@ -248,18 +248,18 @@ static void run(ftl::Configurable *root) { bool busy = false; // Create the source depth map filters - auto *prefilter = ftl::config::create<ftl::Filters>(root, "pre_filters"); - prefilter->create<ftl::filters::ColourChannels>("colour"); - prefilter->create<ftl::filters::DepthSmoother>("hfnoise"); - prefilter->create<ftl::filters::MLSSmoother>("mls"); + auto *prefilter = ftl::config::create<ftl::operators::Graph>(root, "pre_filters"); + prefilter->append<ftl::operators::ColourChannels>("colour"); + prefilter->append<ftl::operators::HFSmoother>("hfnoise"); + prefilter->append<ftl::operators::SimpleMLS>("mls"); - auto *postfilter = ftl::config::create<ftl::Filters>(root, "post_filters"); - postfilter->create<ftl::filters::DepthSmoother>("hfnoise"); - postfilter->create<ftl::filters::MLSSmoother>("mls"); + //auto *postfilter = ftl::config::create<ftl::Filters>(root, "post_filters"); + //postfilter->create<ftl::filters::DepthSmoother>("hfnoise"); + //postfilter->create<ftl::filters::MLSSmoother>("mls"); group->setLatency(4); group->setName("ReconGroup"); - group->sync([splat,virt,&busy,&slave,&scene_A,&scene_B,&align,controls,prefilter,postfilter](ftl::rgbd::FrameSet &fs) -> bool { + group->sync([splat,virt,&busy,&slave,&scene_A,&scene_B,&align,controls,prefilter](ftl::rgbd::FrameSet &fs) -> bool { //cudaSetDevice(scene->getCUDADevice()); //if (slave.isPaused()) return true; @@ -274,7 +274,7 @@ static void run(ftl::Configurable *root) { // Swap the entire frameset to allow rapid return fs.swapTo(scene_A); - ftl::pool.push([&scene_B,&scene_A,&busy,&slave,&align, prefilter, postfilter](int id) { + ftl::pool.push([&scene_B,&scene_A,&busy,&slave,&align, prefilter](int id) { //cudaSetDevice(scene->getCUDADevice()); // TODO: Release frameset here... //cudaSafeCall(cudaStreamSynchronize(scene->getIntegrationStream())); @@ -285,7 +285,7 @@ static void run(ftl::Configurable *root) { for (int i=0; i<scene_A.frames.size(); ++i) { auto &f = scene_A.frames[i]; auto s = scene_A.sources[i]; - prefilter->filter(f, s, 0); + prefilter->apply(f, f, s, 0); } // Send all frames to GPU, block until done? diff --git a/components/operators/CMakeLists.txt b/components/operators/CMakeLists.txt index b631b00ae..a1ef77bd3 100644 --- a/components/operators/CMakeLists.txt +++ b/components/operators/CMakeLists.txt @@ -1,18 +1,18 @@ -add_library(ftlfilter +add_library(ftloperators src/smoothing.cpp src/smoothing.cu - src/filter.cpp + src/operator.cpp src/colours.cpp ) # These cause errors in CI build and are being removed from PCL in newer versions # target_compile_options(ftlrender PUBLIC ${PCL_DEFINITIONS}) -target_include_directories(ftlfilter PUBLIC +target_include_directories(ftloperators PUBLIC ${PCL_INCLUDE_DIRS} $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> $<INSTALL_INTERFACE:include> PRIVATE src) -target_link_libraries(ftlfilter ftlrender ftlrgbd ftlcommon Eigen3::Eigen Threads::Threads ${OpenCV_LIBS}) +target_link_libraries(ftloperators ftlrender ftlrgbd ftlcommon Eigen3::Eigen Threads::Threads ${OpenCV_LIBS}) #ADD_SUBDIRECTORY(test) diff --git a/components/operators/include/ftl/operators/colours.hpp b/components/operators/include/ftl/operators/colours.hpp index 4f611903a..afad434d4 100644 --- a/components/operators/include/ftl/operators/colours.hpp +++ b/components/operators/include/ftl/operators/colours.hpp @@ -1,17 +1,19 @@ -#ifndef _FTL_FILTERS_COLOURS_HPP_ -#define _FTL_FILTERS_COLOURS_HPP_ +#ifndef _FTL_OPERATORS_COLOURS_HPP_ +#define _FTL_OPERATORS_COLOURS_HPP_ -#include <ftl/filters/filter.hpp> +#include <ftl/operators/operator.hpp> namespace ftl { -namespace filters { +namespace operators { -class ColourChannels : public ftl::Filter { +class ColourChannels : public ftl::operators::Operator { public: - explicit ColourChannels(nlohmann::json &config); + explicit ColourChannels(ftl::Configurable *cfg); ~ColourChannels(); - void filter(ftl::rgbd::Frame &frame, ftl::rgbd::Source *src, cudaStream_t stream) override; + inline Operator::Type type() const override { return Operator::Type::OneToOne; } + + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; private: cv::cuda::GpuMat temp_; @@ -20,4 +22,4 @@ class ColourChannels : public ftl::Filter { } } -#endif // _FTL_FILTERS_COLOURS_HPP_ +#endif // _FTL_OPERATORS_COLOURS_HPP_ diff --git a/components/operators/include/ftl/operators/operator.hpp b/components/operators/include/ftl/operators/operator.hpp index f302aaa2f..4d4359e6d 100644 --- a/components/operators/include/ftl/operators/operator.hpp +++ b/components/operators/include/ftl/operators/operator.hpp @@ -1,66 +1,86 @@ -#ifndef _FTL_FILTERS_FILTER_HPP_ -#define _FTL_FILTERS_FILTER_HPP_ +#ifndef _FTL_OPERATORS_OPERATOR_HPP_ +#define _FTL_OPERATORS_OPERATOR_HPP_ #include <list> #include <ftl/configurable.hpp> #include <ftl/configuration.hpp> #include <ftl/rgbd/frame.hpp> +#include <ftl/rgbd/frameset.hpp> #include <ftl/rgbd/source.hpp> #include <ftl/cuda_common.hpp> namespace ftl { -//namespace filters { +namespace operators { /** - * An abstract frame filter interface. Any kind of filter that operates on a + * An abstract frame operator interface. Any kind of filter that operates on a * single frame should use this as a base class. An example of a filter would * be MLS smoothing, or optical flow temporal smoothing. Some 'filters' might * simply generate additional channels, such as a 'Normals' filter that * generates a normals channel. Filters may also have internal data buffers, * these may also persist between frames in some cases. */ -class Filter : public ftl::Configurable { +class Operator { public: - explicit Filter(nlohmann::json &config); - virtual ~Filter(); + explicit Operator(ftl::Configurable *cfg); + virtual ~Operator(); - virtual void filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream)=0; + enum class Type { + OneToOne, // Frame to Frame (Filter or generator) + ManyToOne, // FrameSet to Frame (Rendering or Compositing) + ManyToMany, // FrameSet to FrameSet (alignment) + OneToMany // Currently not used or supported + }; + + /** + * Must be implemented and return an operator structural type. + */ + virtual Type type() const =0; + + virtual bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream); + virtual bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream); + virtual bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *os, cudaStream_t stream); inline void enable() { enabled_ = true; } inline void disable() { enabled_ = false; } inline bool enabled() const { return enabled_; } inline void enabled(bool e) { enabled_ = e; } - protected: + inline ftl::Configurable *config() const { return config_; } + + private: bool enabled_; + ftl::Configurable *config_; }; /** - * Represent a sequential collection of filters. Each filter created is + * Represent a sequential collection of operators. Each operator created is * added to an internal list and then applied to a frame in the order they were * created. */ -class Filters : public ftl::Configurable { +class Graph : public ftl::Configurable { public: - explicit Filters(nlohmann::json &config); - ~Filters(); + explicit Graph(nlohmann::json &config); + ~Graph(); template <typename T> - Filter *create(const std::string &name); + Operator *append(const std::string &name); - void filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream=0); + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream=0); + bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream=0); + bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream=0); private: - std::list<ftl::Filter*> filters_; - Filter *_create(Filter *f); + std::list<ftl::operators::Operator*> operators_; + Operator *_append(Operator *f); }; -//} +} } template <typename T> -ftl::Filter *ftl::Filters::create(const std::string &name) { - return _create(dynamic_cast<ftl::Filter*>(ftl::create<T>(this, name))); +ftl::operators::Operator *ftl::operators::Graph::append(const std::string &name) { + return _append(dynamic_cast<ftl::operators::Operator*>(ftl::create<T>(this, name))); } -#endif // _FTL_FILTERS_FILTER_HPP_ +#endif // _FTL_OPERATORS_OPERATOR_HPP_ diff --git a/components/operators/include/ftl/operators/smoothing.hpp b/components/operators/include/ftl/operators/smoothing.hpp index f6722e9b3..149173036 100644 --- a/components/operators/include/ftl/operators/smoothing.hpp +++ b/components/operators/include/ftl/operators/smoothing.hpp @@ -1,29 +1,63 @@ -#ifndef _FTL_SMOOTHING_HPP_ -#define _FTL_SMOOTHING_HPP_ +#ifndef _FTL_OPERATORS_SMOOTHING_HPP_ +#define _FTL_OPERATORS_SMOOTHING_HPP_ -#include <ftl/filters/filter.hpp> +#include <ftl/operators/operator.hpp> namespace ftl { -namespace filters { +namespace operators { -class DepthSmoother : public ftl::Filter { +/** + * Remove high frequency noise whilst attempting to retain sharp edges and curves. + * It uses the minimum error in the second derivative of the local surface as + * a smoothing factor, with the depth error itself taken from the minimum + * first derivative. Only the depth channel is used and modified. + */ +class HFSmoother : public ftl::operators::Operator { public: - explicit DepthSmoother(nlohmann::json &config); - ~DepthSmoother(); + explicit HFSmoother(ftl::Configurable*); + ~HFSmoother(); - void filter(ftl::rgbd::Frame &frame, ftl::rgbd::Source *src, cudaStream_t stream) override; + inline Operator::Type type() const override { return Operator::Type::OneToOne; } + + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; private: cv::cuda::GpuMat temp_; ftl::rgbd::Frame frames_[4]; }; -class MLSSmoother : public ftl::Filter { +/** + * Perform Moving Least Squares smoothing with a constant smoothing amount and + * neighbourhood size. Requires channels: Depth + Normals. + * Also outputs Depth + Normals. + */ +class SimpleMLS : public ftl::operators::Operator { public: - explicit MLSSmoother(nlohmann::json &config); - ~MLSSmoother(); + explicit SimpleMLS(ftl::Configurable*); + ~SimpleMLS(); + + inline Operator::Type type() const override { return Operator::Type::OneToOne; } + + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; + + private: +}; + +/** + * A version of Moving Least Squares where both the smoothing factor and + * neighbourhood size are adapted over an extra large range using the colour + * channel as a guide. Requires Depth+Normals+Colour. Neighbourhood can + * encompass hundreds of pixels with a smoothing factor approaching a meter, or + * it can be only a few or even no pixels with a zero smoothing factor. + */ +class DynamicColourMLS : public ftl::operators::Operator { + public: + explicit DynamicColourMLS(ftl::Configurable*); + ~DynamicColourMLS(); + + inline Operator::Type type() const override { return Operator::Type::OneToOne; } - void filter(ftl::rgbd::Frame &frame, ftl::rgbd::Source *src, cudaStream_t stream) override; + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; private: }; @@ -31,4 +65,4 @@ class MLSSmoother : public ftl::Filter { } } -#endif // _FTL_SMOOTHING_HPP_ +#endif // _FTL_OPERATORS_SMOOTHING_HPP_ diff --git a/components/operators/src/colours.cpp b/components/operators/src/colours.cpp index 8427ac6f7..3174c42e4 100644 --- a/components/operators/src/colours.cpp +++ b/components/operators/src/colours.cpp @@ -1,9 +1,9 @@ -#include <ftl/filters/colours.hpp> +#include <ftl/operators/colours.hpp> -using ftl::filters::ColourChannels; +using ftl::operators::ColourChannels; using ftl::codecs::Channel; -ColourChannels::ColourChannels(nlohmann::json &config) : ftl::Filter(config) { +ColourChannels::ColourChannels(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) { } @@ -11,14 +11,16 @@ ColourChannels::~ColourChannels() { } -void ColourChannels::filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream) { +bool ColourChannels::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) { // Convert colour from BGR to BGRA if needed - if (f.get<cv::cuda::GpuMat>(Channel::Colour).type() == CV_8UC3) { + if (in.get<cv::cuda::GpuMat>(Channel::Colour).type() == CV_8UC3) { //cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream); // Convert to 4 channel colour - auto &col = f.get<cv::cuda::GpuMat>(Channel::Colour); + auto &col = in.get<cv::cuda::GpuMat>(Channel::Colour); temp_.create(col.size(), CV_8UC4); cv::cuda::swap(col, temp_); cv::cuda::cvtColor(temp_,col, cv::COLOR_BGR2BGRA, 0); } + + return true; } diff --git a/components/operators/src/operator.cpp b/components/operators/src/operator.cpp index 4712ea7e7..14ae77e35 100644 --- a/components/operators/src/operator.cpp +++ b/components/operators/src/operator.cpp @@ -1,35 +1,56 @@ -#include <ftl/filters/filter.hpp> +#include <ftl/operators/operator.hpp> -using ftl::Filter; -using ftl::Filters; +using ftl::operators::Operator; +using ftl::operators::Graph; +using ftl::rgbd::Frame; +using ftl::rgbd::FrameSet; +using ftl::rgbd::Source; -Filter::Filter(nlohmann::json &config) : ftl::Configurable(config) { - enabled_ = value("enabled", true); +Operator::Operator(ftl::Configurable *config) : config_(config) { + enabled_ = config_->value("enabled", true); - on("enabled", [this](const ftl::config::Event &e) { - enabled_ = value("enabled", true); + config_->on("enabled", [this](const ftl::config::Event &e) { + enabled_ = config_->value("enabled", true); }); } -Filter::~Filter() {} +Operator::~Operator() {} -Filters::Filters(nlohmann::json &config) : ftl::Configurable(config) { +bool Operator::apply(Frame &in, Frame &out, Source *s, cudaStream_t stream) { + return false; +} + +bool Operator::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) { + return false; +} + +bool Operator::apply(FrameSet &in, Frame &out, Source *os, cudaStream_t stream) { + return false; +} + + + +Graph::Graph(nlohmann::json &config) : ftl::Configurable(config) { } -Filters::~Filters() { +Graph::~Graph() { } -void Filters::filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream) { - for (auto i : filters_) { +bool Graph::apply(Frame &in, Frame &out, Source *s, cudaStream_t stream) { + if (!value("enabled", true)) return false; + + for (auto i : operators_) { if (i->enabled()) { - i->filter(f, s, stream); + i->apply(in, out, s, stream); } } + + return true; } -Filter *Filters::_create(Filter *f) { - filters_.push_back(f); +Operator *Graph::_append(Operator *f) { + operators_.push_back(f); return f; } diff --git a/components/operators/src/smoothing.cpp b/components/operators/src/smoothing.cpp index b288d3d5b..1657d483a 100644 --- a/components/operators/src/smoothing.cpp +++ b/components/operators/src/smoothing.cpp @@ -1,42 +1,41 @@ -#include <ftl/filters/smoothing.hpp> +#include <ftl/operators/smoothing.hpp> #include "smoothing_cuda.hpp" #include <ftl/cuda/normals.hpp> -using ftl::filters::DepthSmoother; -using ftl::filters::MLSSmoother; +using ftl::operators::HFSmoother; +using ftl::operators::SimpleMLS; using ftl::codecs::Channel; using cv::cuda::GpuMat; -DepthSmoother::DepthSmoother(nlohmann::json &config) : ftl::Filter(config) { +HFSmoother::HFSmoother(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) { } -DepthSmoother::~DepthSmoother() { +HFSmoother::~HFSmoother() { } -void DepthSmoother::filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream) { - float var_thresh = value("variance_threshold", 0.0002f); - //bool do_smooth = value("pre_smooth", false); - int levels = max(0, min(value("levels",0), 4)); - int iters = value("iterations",5); +bool HFSmoother::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) { + float var_thresh = config()->value("variance_threshold", 0.0002f); + int levels = max(0, min(config()->value("levels",0), 4)); + int iters = config()->value("iterations",5); - //if (!do_smooth) return; + // FIXME: in and out are assumed to be the same for (int i=0; i<iters; ++i) { ftl::cuda::smoothing_factor( - f.createTexture<float>(Channel::Depth), - f.createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())), - f.createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())), + in.createTexture<float>(Channel::Depth), + in.createTexture<float>(Channel::Energy, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())), + in.createTexture<float>(Channel::Smoothing, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())), var_thresh, s->parameters(), 0 ); } - LOG(INFO) << "PARAMS DEPTHS " << s->parameters().minDepth << "," << s->parameters().maxDepth; + //LOG(INFO) << "PARAMS DEPTHS " << s->parameters().minDepth << "," << s->parameters().maxDepth; - for (int i=0; i<levels; ++i) { + /*for (int i=0; i<levels; ++i) { var_thresh *= 2.0f; auto &dmat = f.get<GpuMat>(Channel::Depth); cv::cuda::resize(dmat, frames_[i].create<GpuMat>(Channel::Depth), cv::Size(dmat.cols / (2*(i+1)), dmat.rows / (2*(i+1))), 0.0, 0.0, cv::INTER_NEAREST); @@ -51,52 +50,54 @@ void DepthSmoother::filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream cv::cuda::resize(frames_[i].get<GpuMat>(Channel::Smoothing), temp_, f.get<cv::cuda::GpuMat>(Channel::Depth).size(), 0.0, 0.0, cv::INTER_LINEAR); cv::cuda::add(temp_, f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Smoothing)); - } + }*/ //cv::cuda::subtract(f.get<GpuMat>(Channel::Depth), f.get<GpuMat>(Channel::Smoothing), f.get<GpuMat>(Channel::Depth)); + + return true; } // ===== MLS =================================================================== -MLSSmoother::MLSSmoother(nlohmann::json &config) : ftl::Filter(config) { +SimpleMLS::SimpleMLS(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) { } -MLSSmoother::~MLSSmoother() { +SimpleMLS::~SimpleMLS() { } -void MLSSmoother::filter(ftl::rgbd::Frame &f, ftl::rgbd::Source *s, cudaStream_t stream) { - //bool do_smooth = value("mls_smooth", false); - float thresh = value("mls_threshold", 0.04f); - int iters = value("mls_iterations", 1); - int radius = value("mls_radius",2); +bool SimpleMLS::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *s, cudaStream_t stream) { + float thresh = config()->value("mls_threshold", 0.04f); + int iters = config()->value("mls_iterations", 1); + int radius = config()->value("mls_radius",2); - //if (!do_smooth) return; - - if (!f.hasChannel(Channel::Normals)) { + if (!in.hasChannel(Channel::Normals)) { ftl::cuda::normals( - f.createTexture<float4>(Channel::Normals, ftl::rgbd::Format<float4>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())), - f.createTexture<float>(Channel::Depth), + in.createTexture<float4>(Channel::Normals, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())), + in.createTexture<float>(Channel::Depth), s->parameters(), 0 ); } + // FIXME: Assume in and out are the same frame. for (int i=0; i<iters; ++i) { ftl::cuda::mls_smooth( - f.createTexture<float4>(Channel::Normals), - f.createTexture<float4>(Channel::Points, ftl::rgbd::Format<float4>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())), - f.createTexture<float>(Channel::Depth), - f.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(f.get<cv::cuda::GpuMat>(Channel::Depth).size())), + in.createTexture<float4>(Channel::Normals), + in.createTexture<float4>(Channel::Points, ftl::rgbd::Format<float4>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())), + in.createTexture<float>(Channel::Depth), + in.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(in.get<cv::cuda::GpuMat>(Channel::Depth).size())), thresh, radius, s->parameters(), 0 ); - f.swapChannels(Channel::Depth, Channel::Depth2); - f.swapChannels(Channel::Normals, Channel::Points); + in.swapChannels(Channel::Depth, Channel::Depth2); + in.swapChannels(Channel::Normals, Channel::Points); } + + return true; } diff --git a/components/renderers/cpp/include/ftl/render/tri_render.hpp b/components/renderers/cpp/include/ftl/render/tri_render.hpp index ede35069a..60d3dcbf6 100644 --- a/components/renderers/cpp/include/ftl/render/tri_render.hpp +++ b/components/renderers/cpp/include/ftl/render/tri_render.hpp @@ -5,7 +5,7 @@ #include <ftl/rgbd/frameset.hpp> #include <ftl/render/splat_params.hpp> #include <ftl/cuda/points.hpp> -#include <ftl/filters/filter.hpp> +//#include <ftl/filters/filter.hpp> namespace ftl { namespace render { @@ -43,7 +43,7 @@ class Triangular : public ftl::render::Renderer { cudaStream_t stream_; float3 light_pos_; - ftl::Filters *filters_; + //ftl::Filters *filters_; template <typename T> void __reprojectChannel(ftl::rgbd::Frame &, ftl::codecs::Channel in, ftl::codecs::Channel out, cudaStream_t); diff --git a/components/renderers/cpp/src/tri_render.cpp b/components/renderers/cpp/src/tri_render.cpp index 5804da220..6d60a5f66 100644 --- a/components/renderers/cpp/src/tri_render.cpp +++ b/components/renderers/cpp/src/tri_render.cpp @@ -7,7 +7,7 @@ #include <opencv2/core/cuda_stream_accessor.hpp> -#include <ftl/filters/smoothing.hpp> +//#include <ftl/filters/smoothing.hpp> #include <string> @@ -132,8 +132,8 @@ Triangular::Triangular(nlohmann::json &config, ftl::rgbd::FrameSet *fs) : ftl::r cudaSafeCall(cudaStreamCreate(&stream_)); - filters_ = ftl::create<ftl::Filters>(this, "filters"); - filters_->create<ftl::filters::DepthSmoother>("hfnoise"); + //filters_ = ftl::create<ftl::Filters>(this, "filters"); + //filters_->create<ftl::filters::DepthSmoother>("hfnoise"); } Triangular::~Triangular() { -- GitLab