diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp index 457ee985ed636a3cff8ea2a457103b120c1ed8e7..4deb6256e622a1cd9283aeefe2e3520fc72023e3 100644 --- a/applications/reconstruct/src/main.cpp +++ b/applications/reconstruct/src/main.cpp @@ -124,7 +124,7 @@ static void run(ftl::Configurable *root) { net->start(); net->waitConnections(); - + // Check paths for an FTL file to load... auto paths = (*root->get<nlohmann::json>("paths")); for (auto &x : paths.items()) { @@ -165,8 +165,14 @@ static void run(ftl::Configurable *root) { return; } - auto configproxy = ConfigProxy(net); - //configproxy.add(root, "source/disparity", "disparity"); + ConfigProxy *configproxy = nullptr; + if (net->numberOfPeers() > 0) { + configproxy = new ConfigProxy(net); // TODO delete + auto *disparity = ftl::create<ftl::Configurable>(root, "disparity"); + configproxy->add(disparity, "source/disparity/algorithm", "algorithm"); + configproxy->add(disparity, "source/disparity/bilateral_filter", "bilateral_filter"); + configproxy->add(disparity, "source/disparity/optflow_filter", "optflow_filter"); + } // Create scene transform, intended for axis aligning the walls and floor Eigen::Matrix4d transform; diff --git a/applications/vision/src/main.cpp b/applications/vision/src/main.cpp index 7128b93d30863ce9e6709c3d0fe9dd7e74391113..f99754cbf558bb3d0f53fde37763855fac7af128 100644 --- a/applications/vision/src/main.cpp +++ b/applications/vision/src/main.cpp @@ -48,32 +48,6 @@ using std::chrono::milliseconds; using cv::Mat; using json = nlohmann::json; -namespace ftl { -void disparityToDepth(const cv::Mat &disparity, cv::Mat &depth, const cv::Mat &q) { - cv::Matx44d _Q; - q.convertTo(_Q, CV_64F); - - if (depth.empty()) depth = cv::Mat(disparity.size(), CV_32F); - - for( int y = 0; y < disparity.rows; y++ ) { - const float *sptr = disparity.ptr<float>(y); - float *dptr = depth.ptr<float>(y); - - for( int x = 0; x < disparity.cols; x++ ) { - double d = sptr[x]; - cv::Vec4d homg_pt = _Q*cv::Vec4d(x, y, d, 1.0); - //dptr[x] = Vec3d(homg_pt.val); - //dptr[x] /= homg_pt[3]; - dptr[x] = (homg_pt[2] / homg_pt[3]); // Depth in meters - - if( fabs(d) <= FLT_EPSILON ) - dptr[x] = 1000.0f; - } - } -} -}; - - static void run(ftl::Configurable *root) { Universe *net = ftl::create<Universe>(root, "net"); ftl::ctrl::Slave slave(net, root); diff --git a/components/operators/CMakeLists.txt b/components/operators/CMakeLists.txt index 4bdf407c481334459285e1cf5589449375f4185a..a0a38590eb494a3c6268dd725c9ab3c0f9b64edf 100644 --- a/components/operators/CMakeLists.txt +++ b/components/operators/CMakeLists.txt @@ -8,6 +8,13 @@ set(OPERSRC src/normals.cpp src/filling.cpp src/filling.cu + src/nvopticalflow.cpp + src/disparity/optflow_smoothing.cu + src/disparity/optflow_smoothing.cpp + src/disparity/disp2depth.cu + src/disparity/disparity_to_depth.cpp + src/disparity/fixstars_sgm.cpp + src/disparity/bilateral_filter.cpp src/segmentation.cu src/segmentation.cpp ) diff --git a/components/operators/include/ftl/operators/disparity.hpp b/components/operators/include/ftl/operators/disparity.hpp new file mode 100644 index 0000000000000000000000000000000000000000..07b620280ef10b05a544727a1d73d5b311720684 --- /dev/null +++ b/components/operators/include/ftl/operators/disparity.hpp @@ -0,0 +1,96 @@ +#pragma once + +#include <ftl/operators/operator.hpp> +#include <opencv2/cudaoptflow.hpp> + +#include <libsgm.h> + +namespace ftl { +namespace operators { + +/* + * FixstarsSGM https://github.com/fixstars/libSGM + * + * Requires modified version https://gitlab.utu.fi/joseha/libsgm + * + */ +class FixstarsSGM : public ftl::operators::Operator { + public: + explicit FixstarsSGM(ftl::Configurable* cfg); + + ~FixstarsSGM(); + 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: + bool init(); + bool updateParameters(); + + sgm::StereoSGM *ssgm_; + cv::Size size_; + cv::cuda::GpuMat lbw_; + cv::cuda::GpuMat rbw_; + cv::cuda::GpuMat disp_int_; + + int P1_; + int P2_; + int max_disp_; + float uniqueness_; +}; + +class DisparityBilateralFilter : public::ftl::operators::Operator { + public: + explicit DisparityBilateralFilter(ftl::Configurable*); + + ~DisparityBilateralFilter() {}; + + 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::Ptr<cv::cuda::DisparityBilateralFilter> filter_; + cv::cuda::GpuMat disp_int_; + cv::cuda::GpuMat disp_int_result_; + double scale_; + int radius_; + int iter_; + int n_disp_; +}; + +/* + * Calculate depth from disparity + */ +class DisparityToDepth : public ftl::operators::Operator { + public: + explicit DisparityToDepth(ftl::Configurable* cfg) : + ftl::operators::Operator(cfg) {} + + ~DisparityToDepth() {}; + 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; +}; + +/* + * Optical flow smoothing for depth + */ +class OpticalFlowTemporalSmoothing : public ftl::operators::Operator { + public: + explicit OpticalFlowTemporalSmoothing(ftl::Configurable*); + ~OpticalFlowTemporalSmoothing(); + + 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: + bool init(); + + const ftl::codecs::Channel channel_ = ftl::codecs::Channel::Disparity; + cv::cuda::GpuMat history_; + cv::Size size_; + int n_max_; + float threshold_; +}; + +} +} diff --git a/components/operators/include/ftl/operators/opticalflow.hpp b/components/operators/include/ftl/operators/opticalflow.hpp index 1cbd58b76a33e4956fc45fc94afc32804f742fb2..81afc3914b3a3d31975deca14383f319588209d5 100644 --- a/components/operators/include/ftl/operators/opticalflow.hpp +++ b/components/operators/include/ftl/operators/opticalflow.hpp @@ -6,6 +6,10 @@ namespace ftl { namespace operators { +/* + * Compute Optical flow from Channel::Colour (Left) and save the result in + * Channel::Flow using NVidia Optical Flow 1.0 (via OpenCV wrapper). + */ class NVOpticalFlow : public ftl::operators::Operator { public: explicit NVOpticalFlow(ftl::Configurable*); @@ -16,13 +20,13 @@ class NVOpticalFlow : public ftl::operators::Operator { bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; protected: - void init(); + bool init(); private: cv::Size size_; - // TODO: Left to Flow always assumed, could also calculate something else? - const ftl::codecs::Channel channel_in_ = ftl::codecs::Channel::Left; + // TODO: Colour to Flow always assumed, could also calculate something else? + const ftl::codecs::Channel channel_in_ = ftl::codecs::Channel::Colour; const ftl::codecs::Channel channel_out_ = ftl::codecs::Channel::Flow; cv::Ptr<cv::cuda::NvidiaOpticalFlow_1_0> nvof_; diff --git a/components/operators/src/disparity/bilateral_filter.cpp b/components/operators/src/disparity/bilateral_filter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..8c91fac6f317250f7a8af9b85a0c975e217bdfe7 --- /dev/null +++ b/components/operators/src/disparity/bilateral_filter.cpp @@ -0,0 +1,35 @@ +#include <ftl/operators/disparity.hpp> + +using cv::cuda::GpuMat; +using cv::Size; + +using ftl::codecs::Channel; +using ftl::operators::DisparityBilateralFilter; + +DisparityBilateralFilter::DisparityBilateralFilter(ftl::Configurable* cfg) : + ftl::operators::Operator(cfg) { + + scale_ = 16.0; + n_disp_ = cfg->value("n_disp", 256); + radius_ = cfg->value("radius", 7); + iter_ = cfg->value("iter", 13); + filter_ = cv::cuda::createDisparityBilateralFilter(n_disp_ * scale_, radius_, iter_); +} + +bool DisparityBilateralFilter::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, + ftl::rgbd::Source *src, cudaStream_t stream) { + + if (!in.hasChannel(Channel::Disparity) || !in.hasChannel(Channel::Colour)) { + return false; + } + auto cvstream = cv::cuda::StreamAccessor::wrapStream(stream); + const GpuMat &rgb = in.get<GpuMat>(Channel::Colour); + GpuMat &disp_in = in.get<GpuMat>(Channel::Disparity); + GpuMat &disp_out = out.create<GpuMat>(Channel::Disparity); + disp_out.create(disp_in.size(), disp_in.type()); + + disp_in.convertTo(disp_int_, CV_16SC1, scale_, cvstream); + filter_->apply(disp_int_, rgb, disp_int_result_, cvstream); + disp_int_result_.convertTo(disp_out, disp_in.type(), 1.0/scale_, cvstream); + return true; +} \ No newline at end of file diff --git a/components/operators/src/disparity/cuda.hpp b/components/operators/src/disparity/cuda.hpp new file mode 100644 index 0000000000000000000000000000000000000000..d4cf06aaec772869ee3e8f2e8fafab9157115f57 --- /dev/null +++ b/components/operators/src/disparity/cuda.hpp @@ -0,0 +1,15 @@ +#include <ftl/cuda_common.hpp> + +namespace ftl { +namespace cuda { + +void disparity_to_depth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth, + const ftl::rgbd::Camera &c, cudaStream_t &stream); + + +void optflow_filter(cv::cuda::GpuMat &disp, const cv::cuda::GpuMat &optflow, + cv::cuda::GpuMat &history, int n_max, float threshold, + cv::cuda::Stream &stream); + +} +} diff --git a/components/rgbd-sources/src/algorithms/disp2depth.cu b/components/operators/src/disparity/disp2depth.cu similarity index 74% rename from components/rgbd-sources/src/algorithms/disp2depth.cu rename to components/operators/src/disparity/disp2depth.cu index 4b707c4795017cdf38999cd6606d53ff4870ccb5..86a3fc290967fc0a64dd1a61df61badaef0aa833 100644 --- a/components/rgbd-sources/src/algorithms/disp2depth.cu +++ b/components/operators/src/disparity/disp2depth.cu @@ -16,12 +16,12 @@ __global__ void d2d_kernel(cv::cuda::PtrStepSz<float> disp, cv::cuda::PtrStepSz< namespace ftl { namespace cuda { void disparity_to_depth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth, - const ftl::rgbd::Camera &c, cv::cuda::Stream &stream) { + const ftl::rgbd::Camera &c, cudaStream_t &stream) { dim3 grid(1,1,1); - dim3 threads(128, 1, 1); - grid.x = cv::cuda::device::divUp(disparity.cols, 128); + dim3 threads(128, 1, 1); + grid.x = cv::cuda::device::divUp(disparity.cols, 128); grid.y = cv::cuda::device::divUp(disparity.rows, 1); - d2d_kernel<<<grid, threads, 0, cv::cuda::StreamAccessor::getStream(stream)>>>( + d2d_kernel<<<grid, threads, 0, stream>>>( disparity, depth, c); cudaSafeCall( cudaGetLastError() ); } diff --git a/components/operators/src/disparity/disparity_to_depth.cpp b/components/operators/src/disparity/disparity_to_depth.cpp new file mode 100644 index 0000000000000000000000000000000000000000..5951802f0adc960d387a20a4f7f77abd264fb6e8 --- /dev/null +++ b/components/operators/src/disparity/disparity_to_depth.cpp @@ -0,0 +1,22 @@ +#include "ftl/operators/disparity.hpp" +#include "disparity/cuda.hpp" + +using ftl::operators::DisparityToDepth; +using ftl::codecs::Channel; + +using cv::cuda::GpuMat; + +bool DisparityToDepth::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, + ftl::rgbd::Source *src, cudaStream_t stream) { + + if (!in.hasChannel(Channel::Disparity)) { return false; } + + const auto params = src->parameters(); + const GpuMat &disp = in.get<GpuMat>(Channel::Disparity); + + GpuMat &depth = out.create<GpuMat>(Channel::Depth); + depth.create(disp.size(), CV_32FC1); + + ftl::cuda::disparity_to_depth(disp, depth, params, stream); + return true; +} \ No newline at end of file diff --git a/components/operators/src/disparity/fixstars_sgm.cpp b/components/operators/src/disparity/fixstars_sgm.cpp new file mode 100644 index 0000000000000000000000000000000000000000..79a18685ee3ac8732f6721358f8f9d7dc5be4da9 --- /dev/null +++ b/components/operators/src/disparity/fixstars_sgm.cpp @@ -0,0 +1,136 @@ +#include <loguru.hpp> + +#include "ftl/operators/disparity.hpp" + +using cv::Size; +using cv::cuda::GpuMat; + +using ftl::rgbd::Format; +using ftl::codecs::Channel; +using ftl::rgbd::Frame; +using ftl::rgbd::Source; +using ftl::operators::FixstarsSGM; + +FixstarsSGM::FixstarsSGM(ftl::Configurable* cfg) : + ftl::operators::Operator(cfg) { + + ssgm_ = nullptr; + size_ = Size(0, 0); + + uniqueness_ = cfg->value("uniqueness", 0.95f); + P1_ = cfg->value("P1", 10); + P2_ = cfg->value("P2", 120); + max_disp_ = cfg->value("max_disp", 256); + + if (uniqueness_ < 0.0 || uniqueness_ > 1.0) { + uniqueness_ = 1.0; + LOG(WARNING) << "Invalid uniqueness, using default (1.0)"; + } + + if (P1_ <= 0 ) { + P1_ = 10; + LOG(WARNING) << "Invalid value for P1, using default (10)"; + } + + if (P2_ < P1_) { + P2_ = P1_; + LOG(WARNING) << "Invalid value for P2, using value of P1 (" << P1_ << ")"; + } + + if (!(max_disp_ == 256 || max_disp_ == 128)) { + max_disp_ = 256; + LOG(WARNING) << "Invalid value for max_disp, using default value (256)"; + } + + cfg->on("P1", [this, cfg](const ftl::config::Event&) { + int P1 = cfg->value("P1", 0); + if (P1 <= 0) { + LOG(WARNING) << "Invalid value for P1 (" << P1 << ")"; + } + else { + P1_ = P1; + updateParameters(); + } + }); + + cfg->on("P2", [this, cfg](const ftl::config::Event&) { + int P2 = cfg->value("P2", 0); + if (P2 < P1_) { + LOG(WARNING) << "Invalid value for P2 (" << P2 << ")"; + } + else { + P2_ = P2; + updateParameters(); + } + }); + + cfg->on("uniqueness", [this, cfg](const ftl::config::Event&) { + double uniqueness = cfg->value("uniqueness", 0.0); + if (uniqueness < 0.0 || uniqueness > 1.0) { + LOG(WARNING) << "Invalid value for uniqueness (" << uniqueness << ")"; + } + else { + uniqueness_ = uniqueness; + updateParameters(); + } + }); +} + +FixstarsSGM::~FixstarsSGM() { + if (ssgm_) { + delete ssgm_; + } +} + +bool FixstarsSGM::init() { + if (size_ == Size(0, 0)) { return false; } + if (ssgm_) { delete ssgm_; } + lbw_.create(size_, CV_8UC1); + rbw_.create(size_, CV_8UC1); + disp_int_.create(size_, CV_16SC1); + + ssgm_ = new sgm::StereoSGM(size_.width, size_.height, max_disp_, 8, 16, + lbw_.step, disp_int_.step / sizeof(short), + sgm::EXECUTE_INOUT_CUDA2CUDA, + sgm::StereoSGM::Parameters(P1_, P2_, uniqueness_, true) + ); + + return true; +} + +bool FixstarsSGM::updateParameters() { + if (ssgm_ == nullptr) { return false; } + return this->ssgm_->updateParameters( + sgm::StereoSGM::Parameters(P1_, P2_, uniqueness_, true)); +} + +bool FixstarsSGM::apply(Frame &in, Frame &out, Source *src, cudaStream_t stream) { + if (!in.hasChannel(Channel::Left) || !in.hasChannel(Channel::Right)) { + return false; + } + + const auto &l = in.get<GpuMat>(Channel::Left); + const auto &r = in.get<GpuMat>(Channel::Right); + + if (l.size() != size_) { + size_ = l.size(); + if (!init()) { return false; } + } + + auto &disp = out.create<GpuMat>(Channel::Disparity, Format<float>(l.size())); + + auto cvstream = cv::cuda::StreamAccessor::wrapStream(stream); + cv::cuda::cvtColor(l, lbw_, cv::COLOR_BGR2GRAY, 0, cvstream); + cv::cuda::cvtColor(r, rbw_, cv::COLOR_BGR2GRAY, 0, cvstream); + + cvstream.waitForCompletion(); + ssgm_->execute(lbw_.data, rbw_.data, disp_int_.data); + + // GpuMat left_pixels(dispt_, cv::Rect(0, 0, max_disp_, dispt_.rows)); + // left_pixels.setTo(0); + + cv::cuda::threshold(disp_int_, disp_int_, 4096.0f, 0.0f, cv::THRESH_TOZERO_INV, cvstream); + + disp_int_.convertTo(disp, CV_32F, 1.0f / 16.0f, cvstream); + return true; +} diff --git a/components/operators/src/disparity/optflow_smoothing.cpp b/components/operators/src/disparity/optflow_smoothing.cpp new file mode 100644 index 0000000000000000000000000000000000000000..5304da7dc7fc4d7c5e0e4531c90851c3f41a37a4 --- /dev/null +++ b/components/operators/src/disparity/optflow_smoothing.cpp @@ -0,0 +1,95 @@ +#include <loguru.hpp> + +#include "ftl/operators/disparity.hpp" +#include "ftl/offilter.hpp" +#include "disparity/cuda.hpp" + +#ifdef HAVE_OPTFLOW + +using ftl::operators::OpticalFlowTemporalSmoothing; + +using ftl::codecs::Channel; +using ftl::rgbd::Frame; +using ftl::rgbd::Source; + +using cv::Mat; +using cv::Size; + +using std::vector; + +template<typename T> static bool inline isValidDisparity(T d) { return (0.0 < d) && (d < 256.0); } // TODO + +OpticalFlowTemporalSmoothing::OpticalFlowTemporalSmoothing(ftl::Configurable* cfg) : + ftl::operators::Operator(cfg) { + + size_ = Size(0, 0); + + n_max_ = cfg->value("history_size", 7); + if (n_max_ < 1) { + LOG(WARNING) << "History length must be larger than 0, using default (0)"; + n_max_ = 7; + } + + if (n_max_ > 32) { + // TODO: cuda kernel uses fixed size buffer + LOG(WARNING) << "History length can't be larger than 32 (TODO)"; + n_max_ = 32; + } + + threshold_ = cfg->value("threshold", 1.0); + + cfg->on("threshold", [this, &cfg](const ftl::config::Event&) { + float threshold = cfg->value("threshold", 1.0); + if (threshold < 0.0) { + LOG(WARNING) << "invalid threshold " << threshold << ", value must be positive"; + } + else { + threshold_ = threshold; + init(); + } + }); + + cfg->on("history_size", [this, &cfg](const ftl::config::Event&) { + int n_max = cfg->value("history_size", 1.0); + + if (n_max < 1) { + LOG(WARNING) << "History length must be larger than 0"; + } + else if (n_max_ > 32) { + // TODO: cuda kernel uses fixed size buffer + LOG(WARNING) << "History length can't be larger than 32 (TODO)"; + } + else { + n_max_ = n_max; + init(); + } + }); +} + +OpticalFlowTemporalSmoothing::~OpticalFlowTemporalSmoothing() {} + +bool OpticalFlowTemporalSmoothing::init() { + if (size_ == Size(0, 0)) { return false; } + history_.create(cv::Size(size_.width * n_max_, size_.height), CV_32FC1); + history_.setTo(0.0); + return true; +} + +bool OpticalFlowTemporalSmoothing::apply(Frame &in, Frame &out, Source *src, cudaStream_t stream) { + if (!out.hasChannel(channel_) || !in.hasChannel(Channel::Flow)) { return false; } + + auto cvstream = cv::cuda::StreamAccessor::wrapStream(stream); + const cv::cuda::GpuMat &optflow = in.get<cv::cuda::GpuMat>(Channel::Flow); + cv::cuda::GpuMat &data = out.get<cv::cuda::GpuMat>(channel_); + + if (data.size() != size_) { + size_ = data.size(); + if (!init()) { return false; } + } + + ftl::cuda::optflow_filter(data, optflow, history_, n_max_, threshold_, cvstream); + + return true; +} + +#endif // HAVE_OPTFLOW diff --git a/components/rgbd-sources/src/algorithms/offilter.cu b/components/operators/src/disparity/optflow_smoothing.cu similarity index 97% rename from components/rgbd-sources/src/algorithms/offilter.cu rename to components/operators/src/disparity/optflow_smoothing.cu index 6feee5ae1daf9fc8b4b165370dbb8646b1d7b8a1..a7633036fae1e9d20c6a52ae5617466f1b234202 100644 --- a/components/rgbd-sources/src/algorithms/offilter.cu +++ b/components/operators/src/disparity/optflow_smoothing.cu @@ -1,7 +1,9 @@ #include <ftl/cuda_common.hpp> #include <ftl/rgbd/camera.hpp> #include <opencv2/core/cuda_stream_accessor.hpp> -#include <qsort.h> + +#include "disparity/qsort.h" +#include "disparity/cuda.hpp" __device__ void quicksort(float A[], size_t n) { diff --git a/components/rgbd-sources/include/qsort.h b/components/operators/src/disparity/qsort.h similarity index 100% rename from components/rgbd-sources/include/qsort.h rename to components/operators/src/disparity/qsort.h diff --git a/components/operators/src/nvopticalflow.cpp b/components/operators/src/nvopticalflow.cpp index 5d8239365b11d052069e26de93de9cca2a244435..a8b6d406bc7421d48d0cfb15de40d0eb48cafebe 100644 --- a/components/operators/src/nvopticalflow.cpp +++ b/components/operators/src/nvopticalflow.cpp @@ -17,7 +17,7 @@ NVOpticalFlow::NVOpticalFlow(ftl::Configurable* cfg) : NVOpticalFlow::~NVOpticalFlow() { } -void NVOpticalFlow::init() { +bool NVOpticalFlow::init() { nvof_ = cv::cuda::NvidiaOpticalFlow_1_0::create( size_.width, size_.height, cv::cuda::NvidiaOpticalFlow_1_0::NV_OF_PERF_LEVEL_SLOW, @@ -25,12 +25,11 @@ void NVOpticalFlow::init() { left_gray_.create(size_, CV_8UC1); left_gray_prev_.create(size_, CV_8UC1); + return true; } bool NVOpticalFlow::apply(Frame &in, Frame &out, Source *src, cudaStream_t stream) { - if (!in.hasChannel(channel_in_)) { - return true; // false? - } + if (!in.hasChannel(channel_in_)) { return false; } if (in.get<GpuMat>(channel_in_).size() != size_) { size_ = in.get<GpuMat>(channel_in_).size(); diff --git a/components/rgbd-sources/CMakeLists.txt b/components/rgbd-sources/CMakeLists.txt index 7b81e216d9adb11c5898493077bd02dd2121dfbb..6027ab17a7d64110a72dd51e6cfde098c0b0abc7 100644 --- a/components/rgbd-sources/CMakeLists.txt +++ b/components/rgbd-sources/CMakeLists.txt @@ -1,12 +1,11 @@ set(RGBDSRC src/sources/stereovideo/calibrate.cpp src/sources/stereovideo/local.cpp - src/disparity.cpp src/source.cpp src/frame.cpp src/frameset.cpp src/sources/stereovideo/stereovideo.cpp - src/sources/middlebury/middlebury_source.cpp +# src/sources/middlebury/middlebury_source.cpp src/sources/net/net.cpp src/streamer.cpp src/colour.cpp @@ -17,7 +16,6 @@ set(RGBDSRC # src/algorithms/opencv_bm.cpp src/cb_segmentation.cpp src/abr.cpp - src/offilter.cpp src/sources/virtual/virtual.cpp src/sources/ftlfile/file_source.cpp src/sources/ftlfile/player.cpp @@ -34,14 +32,12 @@ if (LibArchive_FOUND) ) endif (LibArchive_FOUND) -if (LIBSGM_FOUND) - list(APPEND RGBDSRC "src/algorithms/fixstars_sgm.cpp") -endif (LIBSGM_FOUND) +#if (LIBSGM_FOUND) +# list(APPEND RGBDSRC "src/algorithms/fixstars_sgm.cpp") +#endif (LIBSGM_FOUND) if (CUDA_FOUND) list(APPEND RGBDSRC - src/algorithms/disp2depth.cu - src/algorithms/offilter.cu # "src/algorithms/opencv_cuda_bm.cpp" # "src/algorithms/opencv_cuda_bp.cpp" # "src/algorithms/rtcensus.cu" diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp index f96ebcd81ed7336ab34ba0e24322587a63fd6c3b..bbcad8c63f923bd92cbda56cb009e88d2ec50eb0 100644 --- a/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp +++ b/components/rgbd-sources/src/algorithms/fixstars_sgm.cpp @@ -42,6 +42,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) { }); #ifdef HAVE_OPTFLOW +/* updateOFDisparityFilter(); on("use_off", [this](const ftl::config::Event&) { @@ -51,6 +52,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) { on("use_off", [this](const ftl::config::Event&) { updateOFDisparityFilter(); }); +*/ #endif init(size_); @@ -136,6 +138,7 @@ bool FixstarsSGM::updateBilateralFilter() { } #ifdef HAVE_OPTFLOW +/* bool FixstarsSGM::updateOFDisparityFilter() { bool enable = value("use_off", false); int off_size = value("off_size", 9); @@ -163,7 +166,7 @@ bool FixstarsSGM::updateOFDisparityFilter() { } return use_off_; -} +}*/ #endif void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) @@ -216,12 +219,14 @@ void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) dispt_scaled.convertTo(disp, CV_32F, 1.0f / 16.0f, stream); #ifdef HAVE_OPTFLOW +/* // TODO: Optical flow filter expects CV_32F if (use_off_) { frame.upload(Channel::Flow, stream); stream.waitForCompletion(); off_.filter(disp, frame.get<GpuMat>(Channel::Flow), stream); } +*/ #endif } diff --git a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp b/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp index 90d330079e177f6adbb41ebbd6c7830bbf87e031..2de1c41ef377570915397ea2758d265fa875b179 100644 --- a/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp +++ b/components/rgbd-sources/src/algorithms/fixstars_sgm.hpp @@ -59,7 +59,7 @@ namespace ftl { cv::cuda::GpuMat dispt_; #ifdef HAVE_OPTFLOW - ftl::rgbd::OFDisparityFilter off_; + //ftl::rgbd::OFDisparityFilter off_; #endif }; }; diff --git a/components/rgbd-sources/src/cuda_algorithms.hpp b/components/rgbd-sources/src/cuda_algorithms.hpp index 439c16cfc21fef08086bb69b7e84b1c8b49fec74..43fff52d0c1d00aa2ff7960456db1fb827ad5cc6 100644 --- a/components/rgbd-sources/src/cuda_algorithms.hpp +++ b/components/rgbd-sources/src/cuda_algorithms.hpp @@ -38,13 +38,6 @@ namespace cuda { void texture_map(const TextureObject<uchar4> &t, TextureObject<float> &f); - void disparity_to_depth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth, - const ftl::rgbd::Camera &c, cv::cuda::Stream &stream); - - void optflow_filter(cv::cuda::GpuMat &disp, const cv::cuda::GpuMat &optflow, - cv::cuda::GpuMat &history, int n_max, float threshold, - cv::cuda::Stream &stream); - } } diff --git a/components/rgbd-sources/src/offilter.cpp b/components/rgbd-sources/src/offilter.cpp deleted file mode 100644 index 8bb3ef601d18156e1b2a1d7600b621ceefa8c2e0..0000000000000000000000000000000000000000 --- a/components/rgbd-sources/src/offilter.cpp +++ /dev/null @@ -1,52 +0,0 @@ -#include "ftl/offilter.hpp" -#include "cuda_algorithms.hpp" - -#ifdef HAVE_OPTFLOW - -#include <loguru.hpp> - -using namespace ftl::rgbd; -using namespace ftl::codecs; - -using cv::Mat; -using cv::Size; - -using std::vector; - -template<typename T> static bool inline isValidDisparity(T d) { return (0.0 < d) && (d < 256.0); } // TODO - -OFDisparityFilter::OFDisparityFilter(Size size, int n_frames, float threshold) : - n_max_(n_frames + 1), threshold_(threshold) -{ - CHECK((n_max_ > 1) && (n_max_ <= 32)) << "History length must be between 0 and 31!"; - disp_old_ = cv::cuda::GpuMat(cv::Size(size.width * n_max_, size.height), CV_32FC1); - - /*nvof_ = cv::cuda::NvidiaOpticalFlow_1_0::create(size.width, size.height, - cv::cuda::NvidiaOpticalFlow_1_0::NV_OF_PERF_LEVEL_SLOW, - true, false, false, 0);*/ - -} - -void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) -{ - frame.upload(Channel::Flow, stream); - const cv::cuda::GpuMat &optflow = frame.get<cv::cuda::GpuMat>(Channel::Flow); - //frame.get<cv::cuda::GpuMat>(Channel::Disparity); - stream.waitForCompletion(); - if (optflow.empty()) { return; } - - cv::cuda::GpuMat &disp = frame.create<cv::cuda::GpuMat>(Channel::Disparity); - ftl::cuda::optflow_filter(disp, optflow, disp_old_, n_max_, threshold_, stream); -} - -void OFDisparityFilter::filter(cv::cuda::GpuMat &disp, cv::cuda::GpuMat &optflow, cv::cuda::Stream &stream) -{ - if (disp.type() != CV_32FC1) { - LOG(ERROR) << "Optical flow filter expects CV_32FC1 (TODO)"; - return; - } - - ftl::cuda::optflow_filter(disp, optflow, disp_old_, n_max_, threshold_, stream); -} - -#endif // HAVE_OPTFLOW diff --git a/components/rgbd-sources/src/source.cpp b/components/rgbd-sources/src/source.cpp index b0ee77a449e33b82641c18aa0c7a039ed42e8626..13cdd5487edf0b7cbc99f7cd9dd7032b43d31185 100644 --- a/components/rgbd-sources/src/source.cpp +++ b/components/rgbd-sources/src/source.cpp @@ -104,8 +104,8 @@ ftl::rgbd::detail::Source *Source::_createFileImpl(const ftl::URI &uri) { if (ftl::is_directory(path)) { if (ftl::is_file(path + "/video.mp4")) { return new StereoVideoSource(this, path); - } else if (ftl::is_file(path + "/im0.png")) { - return new MiddleburySource(this, path); +// } else if (ftl::is_file(path + "/im0.png")) { +// return new MiddleburySource(this, path); } else { LOG(ERROR) << "Directory is not a valid RGBD source: " << path; } diff --git a/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp b/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp index d152d25e5a7d8830e8b555851f94d97b70463e29..229895049061f2308f1a982eab46005a26940548 100644 --- a/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp +++ b/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp @@ -149,7 +149,7 @@ void MiddleburySource::_performDisparity() { //calib_->rectifyStereo(left_, right_, stream_); disp_->compute(rgb_, right_, disp_tmp_, stream_); //disparityToDepth(disp_tmp_, depth_tmp_, params_, stream_); - ftl::cuda::disparity_to_depth(disp_tmp_, depth_, params_, stream_); + //ftl::cuda::disparity_to_depth(disp_tmp_, depth_, params_, stream_); //left_.download(rgb_, stream_); //rgb_ = lsrc_->cachedLeft(); //depth_tmp_.download(depth_, stream_); diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp index dc23f42e5d0fc4d847dd39e5bdf2e9117120a745..0b0cd15a1a584e6811b6483fe36de7bde5293ce3 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp @@ -1,19 +1,19 @@ #include <loguru.hpp> + #include "stereovideo.hpp" -#include <ftl/configuration.hpp> +#include "ftl/configuration.hpp" #ifdef HAVE_OPTFLOW -#include <ftl/operators/opticalflow.hpp> +#include "ftl/operators/opticalflow.hpp" #endif -#include <ftl/threads.hpp> +#include "ftl/operators/disparity.hpp" + +#include "ftl/threads.hpp" #include "calibrate.hpp" #include "local.hpp" #include "disparity.hpp" -#include "cuda_algorithms.hpp" - -#include "cuda_algorithms.hpp" using ftl::rgbd::detail::Calibrate; using ftl::rgbd::detail::LocalSource; @@ -33,13 +33,11 @@ StereoVideoSource::StereoVideoSource(ftl::rgbd::Source *host, const string &file } StereoVideoSource::~StereoVideoSource() { - delete disp_; delete calib_; delete lsrc_; } -void StereoVideoSource::init(const string &file) -{ +void StereoVideoSource::init(const string &file) { capabilities_ = kCapVideo | kCapStereo; if (ftl::is_video(file)) { @@ -64,29 +62,10 @@ void StereoVideoSource::init(const string &file) lsrc_ = ftl::create<LocalSource>(host_, "feed"); } - // Create the source depth map pipeline - pipeline_ = ftl::config::create<ftl::operators::Graph>(host_, "disparity_pipeline"); - /*pipeline1->append<ftl::operators::ColourChannels>("colour"); // Convert BGR to BGRA - pipeline1->append<ftl::operators::HFSmoother>("hfnoise"); // Remove high-frequency noise - pipeline1->append<ftl::operators::Normals>("normals"); // Estimate surface normals - pipeline1->append<ftl::operators::SmoothChannel>("smoothing"); // Generate a smoothing channel - //pipeline1->append<ftl::operators::ScanFieldFill>("filling"); // Generate a smoothing channel - pipeline1->append<ftl::operators::ColourMLS>("mls"); // Perform MLS (using smoothing channel) - */ - cv::Size size = cv::Size(lsrc_->width(), lsrc_->height()); frames_ = std::vector<Frame>(2); -#ifdef HAVE_OPTFLOW - - use_optflow_ = host_->value("use_optflow", false); - LOG(INFO) << "Using optical flow: " << (use_optflow_ ? "true" : "false"); - pipeline_->append<ftl::operators::NVOpticalFlow>("optflow"); - -#endif - calib_ = ftl::create<Calibrate>(host_, "calibration", size, stream_); - if (!calib_->isCalibrated()) LOG(WARNING) << "Cameras are not calibrated!"; // Generate camera parameters from camera matrix @@ -131,20 +110,25 @@ void StereoVideoSource::init(const string &file) }); // left and right masks (areas outside rectified images) - // only left mask used + // only left mask used (not used) cv::cuda::GpuMat mask_r_gpu(lsrc_->height(), lsrc_->width(), CV_8U, 255); cv::cuda::GpuMat mask_l_gpu(lsrc_->height(), lsrc_->width(), CV_8U, 255); - calib_->rectifyStereo(mask_l_gpu, mask_r_gpu, stream_); stream_.waitForCompletion(); - cv::Mat mask_l; mask_l_gpu.download(mask_l); mask_l_ = (mask_l == 0); - disp_ = Disparity::create(host_, "disparity"); - if (!disp_) LOG(FATAL) << "Unknown disparity algorithm : " << *host_->get<ftl::config::json_t>("disparity"); - disp_->setMask(mask_l_); + pipeline_input_ = ftl::config::create<ftl::operators::Graph>(host_, "input"); + #ifdef HAVE_OPTFLOW + pipeline_input_->append<ftl::operators::NVOpticalFlow>("optflow"); + #endif + + pipeline_depth_ = ftl::config::create<ftl::operators::Graph>(host_, "disparity"); + pipeline_depth_->append<ftl::operators::FixstarsSGM>("algorithm"); + pipeline_depth_->append<ftl::operators::OpticalFlowTemporalSmoothing>("optflow_filter"); + pipeline_depth_->append<ftl::operators::DisparityBilateralFilter>("bilateral_filter"); + pipeline_depth_->append<ftl::operators::DisparityToDepth>("calculate_depth"); LOG(INFO) << "StereoVideo source ready..."; ready_ = true; @@ -172,15 +156,6 @@ ftl::rgbd::Camera StereoVideoSource::parameters(Channel chan) { } } -static void disparityToDepth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth, - const cv::Mat &Q, cv::cuda::Stream &stream) { - // Q(3, 2) = -1/Tx - // Q(2, 3) = f - - double val = (1.0f / Q.at<double>(3, 2)) * Q.at<double>(2, 3); - cv::cuda::divide(val, disparity, depth, 1.0f / 1000.0f, -1, stream); -} - bool StereoVideoSource::capture(int64_t ts) { timestamp_ = ts; lsrc_->grab(); @@ -193,33 +168,10 @@ bool StereoVideoSource::retrieve() { auto &left = frame.create<cv::cuda::GpuMat>(Channel::Left); auto &right = frame.create<cv::cuda::GpuMat>(Channel::Right); lsrc_->get(left, right, calib_, stream2_); - pipeline_->apply(frame, frame, (ftl::rgbd::Source*) lsrc_, cv::cuda::StreamAccessor::getStream(stream2_)); - -#ifdef HAVE_OPTFLOW - // see comments in https://gitlab.utu.fi/nicolas.pope/ftl/issues/155 - /* - if (use_optflow_) - { - auto &left_gray = frame.create<cv::cuda::GpuMat>(Channel::LeftGray); - auto &right_gray = frame.create<cv::cuda::GpuMat>(Channel::RightGray); - - cv::cuda::cvtColor(left, left_gray, cv::COLOR_BGR2GRAY, 0, stream2_); - cv::cuda::cvtColor(right, right_gray, cv::COLOR_BGR2GRAY, 0, stream2_); - - if (frames_[1].hasChannel(Channel::LeftGray)) - { - //frames_[1].download(Channel::LeftGray); - auto &left_gray_prev = frames_[1].get<cv::cuda::GpuMat>(Channel::LeftGray); - auto &optflow = frame.create<cv::cuda::GpuMat>(Channel::Flow); - nvof_->calc(left_gray, left_gray_prev, optflow, stream2_); - // nvof_->upSampler() isn't implemented with CUDA - // cv::cuda::resize() does not work wiht 2-channel input - // cv::cuda::resize(optflow_, optflow, left.size(), 0.0, 0.0, cv::INTER_NEAREST, stream2_); - } - }*/ -#endif + pipeline_input_->apply(frame, frame, host_, cv::cuda::StreamAccessor::getStream(stream2_)); stream2_.waitForCompletion(); + return true; } @@ -231,37 +183,32 @@ void StereoVideoSource::swap() { bool StereoVideoSource::compute(int n, int b) { auto &frame = frames_[1]; - auto &left = frame.get<cv::cuda::GpuMat>(Channel::Left); - auto &right = frame.get<cv::cuda::GpuMat>(Channel::Right); - + const ftl::codecs::Channel chan = host_->getChannel(); - if (left.empty() || right.empty()) return false; + if (!frame.hasChannel(Channel::Left) || !frame.hasChannel(Channel::Right)) { + return false; + } if (chan == Channel::Depth) { - disp_->compute(frame, stream_); - - auto &disp = frame.get<cv::cuda::GpuMat>(Channel::Disparity); - auto &depth = frame.create<cv::cuda::GpuMat>(Channel::Depth); - if (depth.empty()) depth = cv::cuda::GpuMat(left.size(), CV_32FC1); - - ftl::cuda::disparity_to_depth(disp, depth, params_, stream_); - - //left.download(rgb_, stream_); - //depth.download(depth_, stream_); - //frame.download(Channel::Left + Channel::Depth); + pipeline_depth_->apply(frame, frame, host_, cv::cuda::StreamAccessor::getStream(stream_)); stream_.waitForCompletion(); - host_->notify(timestamp_, left, depth); + host_->notify(timestamp_, + frame.get<cv::cuda::GpuMat>(Channel::Left), + frame.get<cv::cuda::GpuMat>(Channel::Depth)); + } else if (chan == Channel::Right) { - //left.download(rgb_, stream_); - //right.download(depth_, stream_); - stream_.waitForCompletion(); // TODO:(Nick) Move to getFrames - host_->notify(timestamp_, left, right); + stream_.waitForCompletion(); // TODO:(Nick) Move to getFrames + host_->notify(timestamp_, + frame.get<cv::cuda::GpuMat>(Channel::Left), + frame.get<cv::cuda::GpuMat>(Channel::Right)); + } else { - //left.download(rgb_, stream_); - stream_.waitForCompletion(); // TODO:(Nick) Move to getFrames - //LOG(INFO) << "NO SECOND CHANNEL: " << (bool)depth_.empty(); + stream_.waitForCompletion(); // TODO:(Nick) Move to getFrames + auto &left = frame.get<cv::cuda::GpuMat>(Channel::Left); depth_.create(left.size(), left.type()); - host_->notify(timestamp_, left, depth_); + host_->notify(timestamp_, + frame.get<cv::cuda::GpuMat>(Channel::Left), + depth_); } return true; diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp index eb29186770fd0fe2347be20653ff51ec9b5080b4..78fcdbcf809eeae0d5de6da30b99ce3dc07f9214 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp @@ -34,17 +34,14 @@ class StereoVideoSource : public detail::Source { bool isReady(); Camera parameters(ftl::codecs::Channel chan); - //const cv::Mat &getRight() const { return right_; } - private: LocalSource *lsrc_; Calibrate *calib_; - Disparity *disp_; - ftl::operators::Graph *pipeline_; + ftl::operators::Graph *pipeline_input_; + ftl::operators::Graph *pipeline_depth_; bool ready_; - bool use_optflow_; cv::cuda::Stream stream_; cv::cuda::Stream stream2_; @@ -53,12 +50,6 @@ class StereoVideoSource : public detail::Source { cv::Mat mask_l_; -#ifdef HAVE_OPTFLOW - // see comments in https://gitlab.utu.fi/nicolas.pope/ftl/issues/155 - cv::Ptr<cv::cuda::NvidiaOpticalFlow_1_0> nvof_; - cv::cuda::GpuMat optflow_; -#endif - void init(const std::string &); }; diff --git a/config/config_vision.jsonc b/config/config_vision.jsonc index b73446cefe06aaaf3663b8fe2823822878b5a1a8..cea950e0c21bde19d369ad0a4f53c255657e3724 100644 --- a/config/config_vision.jsonc +++ b/config/config_vision.jsonc @@ -9,53 +9,6 @@ } }, - "disparity": { - "libsgm": { - "algorithm": "libsgm", - "width": 1280, - "height": 720, - "use_cuda": true, - "minimum": 0, - "maximum": 256, - "tau": 0.0, - "gamma": 0.0, - "window_size": 5, - "sigma": 1.5, - "lambda": 8000.0, - "uniqueness": 0.65, - "use_filter": true, - "P1": 8, - "P2": 130, - "filter_radius": 11, - "filter_iter": 2, - "use_off": true, - "off_size": 24, - "off_threshold": 0.75, - "T": 60, - "T_add": 0, - "T_del": 25, - "T_x" : 3.0, - "alpha" : 0.6, - "beta" : 1.7, - "epsilon" : 15.0 - }, - - "rtcensus": { - "algorithm": "rtcensus", - "use_cuda": true, - "minimum": 0, - "maximum": 256, - "tau": 0.0, - "gamma": 0.0, - "window_size": 5, - "sigma": 1.5, - "lambda": 8000.0, - "use_filter": true, - "filter_radius": 3, - "filter_iter": 4 - } - }, - "sources": { "stereocam": { "uri": "device:video", @@ -71,7 +24,23 @@ }, "use_optflow" : true, "calibration": { "$ref": "#calibrations/default" }, - "disparity": { "$ref": "#disparity/libsgm" } + "disparity": { + "algorithm" : { + "P1" : 10, + "P2" : 120, + "enabled" : true + }, + "bilateral_filter" : { + "radius" : 17, + "iter" : 21, + "enabled" : true + }, + "optflow_filter" : { + "threshold" : 0.8, + "history_size" : 10, + "enabled": true + } + } }, "stereovid": {}, "localhost": {}