Skip to content
Snippets Groups Projects
Commit 1fe12f55 authored by Sebastian Hahta's avatar Sebastian Hahta
Browse files

WIP: optical flow filter

parent d8979e6c
No related branches found
No related tags found
1 merge request!161feature/vision operator
Pipeline #16245 passed
This commit is part of merge request !161. Comments created here will be created in the context of that merge request.
Showing with 74 additions and 30 deletions
...@@ -9,6 +9,8 @@ add_library(ftloperators ...@@ -9,6 +9,8 @@ add_library(ftloperators
src/filling.cpp src/filling.cpp
src/filling.cu src/filling.cu
src/nvopticalflow.cpp src/nvopticalflow.cpp
src/disparity/optflow_smoothing.cpp
src/disparity/optflow_smoothing.cu
) )
# 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
......
#pragma once
#include <ftl/operators/operator.hpp>
#include <opencv2/cudaoptflow.hpp>
namespace ftl {
namespace operators {
/*
* Optical flow smoothing for disparity (or depth)
*/
class DisparitySmoothingOF : public ftl::operators::Operator {
public:
explicit DisparitySmoothingOF(ftl::Configurable*);
~DisparitySmoothingOF();
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 history_;
};
}
}
#include <loguru.hpp>
#include "ftl/operators/disparity.hpp"
#include "ftl/offilter.hpp" #include "ftl/offilter.hpp"
#include "cuda_algorithms.hpp" #include "disparity/optflow_smoothing.hpp"
#ifdef HAVE_OPTFLOW #ifdef HAVE_OPTFLOW
#include <loguru.hpp> using ftl::operators::DisparitySmoothingOF;
using namespace ftl::rgbd; using ftl::codecs::Channel;
using namespace ftl::codecs; using ftl::rgbd::Frame;
using ftl::rgbd::Source;
using cv::Mat; using cv::Mat;
using cv::Size; using cv::Size;
...@@ -15,18 +19,19 @@ using std::vector; ...@@ -15,18 +19,19 @@ using std::vector;
template<typename T> static bool inline isValidDisparity(T d) { return (0.0 < d) && (d < 256.0); } // TODO 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) : DisparitySmoothingOF::DisparitySmoothingOF(ftl::Configurable* cfg) :
n_max_(n_frames + 1), threshold_(threshold) ftl::operators::Operator(cfg) {
{ // TODO read params
/*
CHECK((n_max_ > 1) && (n_max_ <= 32)) << "History length must be between 0 and 31!"; 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); 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);*/
} }
DisparitySmoothingOF::~DisparitySmoothingOF() {}
bool DisparitySmoothingOF::apply(Frame &in, Frame &out, Source *src, cudaStream_t stream) {
/*
void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream)
{ {
frame.upload(Channel::Flow, stream); frame.upload(Channel::Flow, stream);
...@@ -38,15 +43,8 @@ void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream ...@@ -38,15 +43,8 @@ void OFDisparityFilter::filter(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream
cv::cuda::GpuMat &disp = frame.create<cv::cuda::GpuMat>(Channel::Disparity); cv::cuda::GpuMat &disp = frame.create<cv::cuda::GpuMat>(Channel::Disparity);
ftl::cuda::optflow_filter(disp, optflow, disp_old_, n_max_, threshold_, stream); 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) return true;
{
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 #endif // HAVE_OPTFLOW
#include <ftl/cuda_common.hpp> #include <ftl/cuda_common.hpp>
#include <ftl/rgbd/camera.hpp> #include <ftl/rgbd/camera.hpp>
#include <opencv2/core/cuda_stream_accessor.hpp> #include <opencv2/core/cuda_stream_accessor.hpp>
#include <qsort.h>
#include "disparity/qsort.h"
#include "optflow_smoothing.hpp"
__device__ void quicksort(float A[], size_t n) __device__ void quicksort(float A[], size_t n)
{ {
......
#include <ftl/cuda_common.hpp>
namespace ftl {
namespace cuda {
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);
}
}
...@@ -17,7 +17,6 @@ set(RGBDSRC ...@@ -17,7 +17,6 @@ set(RGBDSRC
# src/algorithms/opencv_bm.cpp # src/algorithms/opencv_bm.cpp
src/cb_segmentation.cpp src/cb_segmentation.cpp
src/abr.cpp src/abr.cpp
src/offilter.cpp
src/sources/virtual/virtual.cpp src/sources/virtual/virtual.cpp
src/sources/ftlfile/file_source.cpp src/sources/ftlfile/file_source.cpp
src/sources/ftlfile/player.cpp src/sources/ftlfile/player.cpp
...@@ -41,7 +40,6 @@ endif (LIBSGM_FOUND) ...@@ -41,7 +40,6 @@ endif (LIBSGM_FOUND)
if (CUDA_FOUND) if (CUDA_FOUND)
list(APPEND RGBDSRC list(APPEND RGBDSRC
src/algorithms/disp2depth.cu src/algorithms/disp2depth.cu
src/algorithms/offilter.cu
# "src/algorithms/opencv_cuda_bm.cpp" # "src/algorithms/opencv_cuda_bm.cpp"
# "src/algorithms/opencv_cuda_bp.cpp" # "src/algorithms/opencv_cuda_bp.cpp"
# "src/algorithms/rtcensus.cu" # "src/algorithms/rtcensus.cu"
......
...@@ -42,6 +42,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) { ...@@ -42,6 +42,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) {
}); });
#ifdef HAVE_OPTFLOW #ifdef HAVE_OPTFLOW
/*
updateOFDisparityFilter(); updateOFDisparityFilter();
on("use_off", [this](const ftl::config::Event&) { on("use_off", [this](const ftl::config::Event&) {
...@@ -51,6 +52,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) { ...@@ -51,6 +52,7 @@ FixstarsSGM::FixstarsSGM(nlohmann::json &config) : Disparity(config) {
on("use_off", [this](const ftl::config::Event&) { on("use_off", [this](const ftl::config::Event&) {
updateOFDisparityFilter(); updateOFDisparityFilter();
}); });
*/
#endif #endif
init(size_); init(size_);
...@@ -136,6 +138,7 @@ bool FixstarsSGM::updateBilateralFilter() { ...@@ -136,6 +138,7 @@ bool FixstarsSGM::updateBilateralFilter() {
} }
#ifdef HAVE_OPTFLOW #ifdef HAVE_OPTFLOW
/*
bool FixstarsSGM::updateOFDisparityFilter() { bool FixstarsSGM::updateOFDisparityFilter() {
bool enable = value("use_off", false); bool enable = value("use_off", false);
int off_size = value("off_size", 9); int off_size = value("off_size", 9);
...@@ -163,7 +166,7 @@ bool FixstarsSGM::updateOFDisparityFilter() { ...@@ -163,7 +166,7 @@ bool FixstarsSGM::updateOFDisparityFilter() {
} }
return use_off_; return use_off_;
} }*/
#endif #endif
void FixstarsSGM::compute(ftl::rgbd::Frame &frame, cv::cuda::Stream &stream) 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) ...@@ -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); dispt_scaled.convertTo(disp, CV_32F, 1.0f / 16.0f, stream);
#ifdef HAVE_OPTFLOW #ifdef HAVE_OPTFLOW
/*
// TODO: Optical flow filter expects CV_32F // TODO: Optical flow filter expects CV_32F
if (use_off_) { if (use_off_) {
frame.upload(Channel::Flow, stream); frame.upload(Channel::Flow, stream);
stream.waitForCompletion(); stream.waitForCompletion();
off_.filter(disp, frame.get<GpuMat>(Channel::Flow), stream); off_.filter(disp, frame.get<GpuMat>(Channel::Flow), stream);
} }
*/
#endif #endif
} }
......
...@@ -59,7 +59,7 @@ namespace ftl { ...@@ -59,7 +59,7 @@ namespace ftl {
cv::cuda::GpuMat dispt_; cv::cuda::GpuMat dispt_;
#ifdef HAVE_OPTFLOW #ifdef HAVE_OPTFLOW
ftl::rgbd::OFDisparityFilter off_; //ftl::rgbd::OFDisparityFilter off_;
#endif #endif
}; };
}; };
......
...@@ -41,10 +41,6 @@ namespace cuda { ...@@ -41,10 +41,6 @@ namespace cuda {
void disparity_to_depth(const cv::cuda::GpuMat &disparity, cv::cuda::GpuMat &depth, 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, 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);
} }
} }
......
...@@ -194,6 +194,9 @@ void StereoVideoSource::swap() { ...@@ -194,6 +194,9 @@ void StereoVideoSource::swap() {
bool StereoVideoSource::compute(int n, int b) { bool StereoVideoSource::compute(int n, int b) {
auto &frame = frames_[1]; auto &frame = frames_[1];
pipeline_depth_->apply(frame, frame, host_, cv::cuda::StreamAccessor::getStream(stream_));
auto &left = frame.get<cv::cuda::GpuMat>(Channel::Left); auto &left = frame.get<cv::cuda::GpuMat>(Channel::Left);
auto &right = frame.get<cv::cuda::GpuMat>(Channel::Right); auto &right = frame.get<cv::cuda::GpuMat>(Channel::Right);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment