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

Implements #250 clipping operator

parent 0264cc0c
No related branches found
No related tags found
No related merge requests found
...@@ -37,6 +37,7 @@ ...@@ -37,6 +37,7 @@
#include <ftl/operators/segmentation.hpp> #include <ftl/operators/segmentation.hpp>
#include <ftl/operators/mask.hpp> #include <ftl/operators/mask.hpp>
#include <ftl/operators/antialiasing.hpp> #include <ftl/operators/antialiasing.hpp>
#include <ftl/operators/clipping.hpp>
#include <ftl/cuda/normals.hpp> #include <ftl/cuda/normals.hpp>
#include <ftl/registration.hpp> #include <ftl/registration.hpp>
...@@ -320,6 +321,7 @@ static void run(ftl::Configurable *root) { ...@@ -320,6 +321,7 @@ static void run(ftl::Configurable *root) {
// Create the source depth map pipeline // Create the source depth map pipeline
auto *pipeline1 = ftl::config::create<ftl::operators::Graph>(root, "pre_filters"); auto *pipeline1 = ftl::config::create<ftl::operators::Graph>(root, "pre_filters");
pipeline1->append<ftl::operators::ClipScene>("clipping");
pipeline1->append<ftl::operators::ColourChannels>("colour"); // Convert BGR to BGRA pipeline1->append<ftl::operators::ColourChannels>("colour"); // Convert BGR to BGRA
//pipeline1->append<ftl::operators::HFSmoother>("hfnoise"); // Remove high-frequency noise //pipeline1->append<ftl::operators::HFSmoother>("hfnoise"); // Remove high-frequency noise
pipeline1->append<ftl::operators::Normals>("normals"); // Estimate surface normals pipeline1->append<ftl::operators::Normals>("normals"); // Estimate surface normals
......
...@@ -17,6 +17,7 @@ set(OPERSRC ...@@ -17,6 +17,7 @@ set(OPERSRC
src/mask.cpp src/mask.cpp
src/antialiasing.cpp src/antialiasing.cpp
src/antialiasing.cu src/antialiasing.cu
src/clipping.cpp
) )
......
#ifndef _FTL_OPERATORS_CLIPPING_HPP_
#define _FTL_OPERATORS_CLIPPING_HPP_
#include <ftl/operators/operator.hpp>
#include <ftl/cuda_common.hpp>
namespace ftl {
namespace operators {
/**
* Calculate rough normals from local depth gradients.
*/
class ClipScene : public ftl::operators::Operator {
public:
explicit ClipScene(ftl::Configurable*);
~ClipScene();
inline Operator::Type type() const override { return Operator::Type::ManyToMany; }
bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream) override;
};
}
}
#endif // _FTL_OPERATORS_CLIPPING_HPP_
#include <ftl/operators/clipping.hpp>
#include <ftl/cuda/points.hpp>
#include <ftl/utility/matrix_conversion.hpp>
using ftl::operators::ClipScene;
using ftl::codecs::Channel;
using ftl::rgbd::Format;
ClipScene::ClipScene(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) {
}
ClipScene::~ClipScene() {
}
// TODO: Put in common place
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;
}
bool ClipScene::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream) {
auto &c = *config();
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);
ftl::cuda::ClipSpace clip;
clip.origin = MatrixConversion::toCUDA(r.matrix() * t.matrix());
clip.size = make_float3(width, height, depth);
for (size_t i=0; i<in.frames.size(); ++i) {
auto &f = in.frames[i];
auto *s = in.sources[i];
auto pose = MatrixConversion::toCUDA(s->getPose().cast<float>());
auto sclip = clip;
sclip.origin = sclip.origin * pose;
ftl::cuda::clipping(f.createTexture<float>(Channel::Depth), s->parameters(), sclip, stream);
}
return true;
}
...@@ -46,16 +46,32 @@ bool Graph::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) { ...@@ -46,16 +46,32 @@ bool Graph::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) {
if (in.frames.size() != out.frames.size()) return false; if (in.frames.size() != out.frames.size()) return false;
for (auto &i : operators_) { for (auto &i : operators_) {
// Make sure there are enough instances if (i.instances.size() < 1) {
while (i.instances.size() < in.frames.size()) {
i.instances.push_back(i.maker->make()); i.instances.push_back(i.maker->make());
} }
for (int j=0; j<in.frames.size(); ++j) { if (i.instances[0]->type() == Operator::Type::OneToOne) {
auto *instance = i.instances[j]; // Make sure there are enough instances
while (i.instances.size() < in.frames.size()) {
i.instances.push_back(i.maker->make());
}
for (int j=0; j<in.frames.size(); ++j) {
auto *instance = i.instances[j];
if (instance->enabled()) {
instance->apply(in.frames[j], out.frames[j], in.sources[j], stream_actual);
}
}
} else if (i.instances[0]->type() == Operator::Type::ManyToMany) {
auto *instance = i.instances[0];
if (instance->enabled()) { if (instance->enabled()) {
instance->apply(in.frames[j], out.frames[j], in.sources[j], stream_actual); try {
instance->apply(in, out, stream_actual);
} catch (const std::exception &e) {
LOG(ERROR) << "Operator exception: " << e.what();
}
} }
} }
} }
......
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