diff --git a/applications/calibration-multi/src/main.cpp b/applications/calibration-multi/src/main.cpp index dbea22842d4b0a70546187f48e161def746af207..7c92ea9eaffcf68f1af97c47e1255d95b5a533cc 100644 --- a/applications/calibration-multi/src/main.cpp +++ b/applications/calibration-multi/src/main.cpp @@ -395,37 +395,6 @@ void runCameraCalibration( ftl::Configurable* root, const size_t n_cameras = n_sources * 2; size_t reference_camera = 0; - { - auto camera = sources[0]->parameters(); - params.size = Size(camera.width, camera.height); - LOG(INFO) << "Camera resolution: " << params.size; - } - - params.idx_cameras.resize(n_cameras); - std::iota(params.idx_cameras.begin(), params.idx_cameras.end(), 0); - - // TODO: parameter for calibration target type - auto calib = MultiCameraCalibrationNew( n_cameras, reference_camera, - params.size, CalibrationTarget(0.250) - ); - - for (size_t i = 0; i < n_sources; i++) { - auto camera_r = sources[i]->parameters(Channel::Right); - auto camera_l = sources[i]->parameters(Channel::Left); - - CHECK(params.size == Size(camera_r.width, camera_r.height)); - CHECK(params.size == Size(camera_l.width, camera_l.height)); - - Mat K; - K = createCameraMatrix(camera_r); - LOG(INFO) << "K[" << 2 * i + 1 << "] = \n" << K; - calib.setCameraParameters(2 * i + 1, K); - - K = createCameraMatrix(camera_l); - LOG(INFO) << "K[" << 2 * i << "] = \n" << K; - calib.setCameraParameters(2 * i, K); - } - ftl::rgbd::Group group; for (Source* src : sources) { src->setChannel(Channel::Right); @@ -442,6 +411,8 @@ void runCameraCalibration( ftl::Configurable* root, mutex.lock(); bool good = true; for (size_t i = 0; i < frames.sources.size(); i ++) { + frames.frames[i].download(Channel::Left+Channel::Right); + if (frames.frames[i].get<cv::Mat>(Channel::Left).empty()) good = false; if (frames.frames[i].get<cv::Mat>(Channel::Right).empty()) good = false; if (frames.frames[i].get<cv::Mat>(Channel::Left).channels() != 3) good = false; // ASSERT @@ -455,6 +426,43 @@ void runCameraCalibration( ftl::Configurable* root, mutex.unlock(); return true; }); + + for (auto &source : sources) { + while (!source->isReady()) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + } + + { + auto camera = sources[0]->parameters(); + params.size = Size(camera.width, camera.height); + LOG(INFO) << "Camera resolution: " << params.size; + } + + params.idx_cameras.resize(n_cameras); + std::iota(params.idx_cameras.begin(), params.idx_cameras.end(), 0); + + // TODO: parameter for calibration target type + auto calib = MultiCameraCalibrationNew( n_cameras, reference_camera, + params.size, CalibrationTarget(0.250) + ); + + for (size_t i = 0; i < n_sources; i++) { + auto camera_r = sources[i]->parameters(Channel::Right); + auto camera_l = sources[i]->parameters(); + + CHECK(params.size == Size(camera_r.width, camera_r.height)); + CHECK(params.size == Size(camera_l.width, camera_l.height)); + + Mat K; + K = createCameraMatrix(camera_r); + LOG(INFO) << "K[" << 2 * i + 1 << "] = \n" << K; + calib.setCameraParameters(2 * i + 1, K); + + K = createCameraMatrix(camera_l); + LOG(INFO) << "K[" << 2 * i << "] = \n" << K; + calib.setCameraParameters(2 * i, K); + } int iter = 0; Mat show; diff --git a/applications/ftl2mkv/src/main.cpp b/applications/ftl2mkv/src/main.cpp index b555dcbf7f3494dbd66f87415f51cbb0cec3c49e..a6a7a2448869168e7634ecd40ba724ca964bdda5 100644 --- a/applications/ftl2mkv/src/main.cpp +++ b/applications/ftl2mkv/src/main.cpp @@ -99,7 +99,7 @@ int main(int argc, char **argv) { AVOutputFormat *fmt; AVFormatContext *oc; - AVStream *video_st[10] = {nullptr}; + AVStream *video_st[10][2] = {nullptr}; av_register_all(); @@ -130,28 +130,24 @@ int main(int argc, char **argv) { LOG(INFO) << "Converting..."; int current_stream = root->value("stream", 0); - int current_channel = 0; + int current_channel = root->value("channel", -1); //bool stream_added[10] = {false}; // TODO: In future, find a better way to discover number of streams... // Read entire file to find all streams before reading again to write data bool res = r.read(90000000000000, [¤t_stream,¤t_channel,&r,&video_st,oc](const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - if (spkt.channel != static_cast<ftl::codecs::Channel>(current_channel)) return; + if (spkt.channel != static_cast<ftl::codecs::Channel>(current_channel) && current_channel != -1) return; if (spkt.streamID == current_stream || current_stream == 255) { - if (pkt.codec == codec_t::POSE) { - return; - } - - if (pkt.codec == codec_t::CALIBRATION) { + if (pkt.codec != codec_t::HEVC) { return; } if (spkt.streamID >= 10) return; // TODO: Allow for more than 10 - if (video_st[spkt.streamID] == nullptr) { - video_st[spkt.streamID] = add_video_stream(oc, pkt); + if (video_st[spkt.streamID][(spkt.channel == Channel::Left) ? 0 : 1] == nullptr) { + video_st[spkt.streamID][(spkt.channel == Channel::Left) ? 0 : 1] = add_video_stream(oc, pkt); } } }); @@ -172,14 +168,10 @@ int main(int argc, char **argv) { bool seen_key[10] = {false}; res = r.read(90000000000000, [¤t_stream,¤t_channel,&r,&video_st,oc,&seen_key](const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - if (spkt.channel != static_cast<ftl::codecs::Channel>(current_channel)) return; + if (spkt.channel != static_cast<ftl::codecs::Channel>(current_channel) && current_channel != -1) return; if (spkt.streamID == current_stream || current_stream == 255) { - if (pkt.codec == codec_t::POSE) { - return; - } - - if (pkt.codec == codec_t::CALIBRATION) { + if (pkt.codec != codec_t::HEVC) { return; } @@ -201,7 +193,7 @@ int main(int argc, char **argv) { if (keyframe) avpkt.flags |= AV_PKT_FLAG_KEY; avpkt.pts = spkt.timestamp - r.getStartTime(); avpkt.dts = avpkt.pts; - avpkt.stream_index= video_st[spkt.streamID]->index; + avpkt.stream_index= video_st[spkt.streamID][(spkt.channel == Channel::Left) ? 0 : 1]->index; avpkt.data= const_cast<uint8_t*>(pkt.data.data()); avpkt.size= pkt.data.size(); avpkt.duration = 1; @@ -220,7 +212,8 @@ int main(int argc, char **argv) { //avcodec_close(video_st->codec); for (int i=0; i<10; ++i) { - if (video_st[i]) av_free(video_st[i]); + if (video_st[i][0]) av_free(video_st[i][0]); + if (video_st[i][1]) av_free(video_st[i][1]); } if (!(fmt->flags & AVFMT_NOFILE)) { diff --git a/applications/gui/src/camera.cpp b/applications/gui/src/camera.cpp index ae0d5627a94a84afb819a9b1daf62b6bddacccae..e8a0c80aa8cbe3e90619297a78d2fde7efa7e75b 100644 --- a/applications/gui/src/camera.cpp +++ b/applications/gui/src/camera.cpp @@ -3,6 +3,8 @@ #include "screen.hpp" #include <nanogui/glutil.h> +#include <fstream> + #ifdef HAVE_OPENVR #include "vr.hpp" #endif @@ -137,6 +139,13 @@ ftl::gui::Camera::Camera(ftl::gui::Screen *screen, ftl::rgbd::Source *src) : scr sdepth_ = false; ftime_ = (float)glfwGetTime(); pause_ = false; + recording_ = false; + fileout_ = new std::ofstream(); + writer_ = new ftl::codecs::Writer(*fileout_); + recorder_ = std::function([this](ftl::rgbd::Source *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { + ftl::codecs::StreamPacket s = spkt; + writer_->write(s, pkt); + }); channel_ = Channel::Left; @@ -166,7 +175,8 @@ ftl::gui::Camera::Camera(ftl::gui::Screen *screen, ftl::rgbd::Source *src) : scr } ftl::gui::Camera::~Camera() { - + delete writer_; + delete fileout_; } ftl::rgbd::Source *ftl::gui::Camera::source() { @@ -494,6 +504,37 @@ const GLTexture &ftl::gui::Camera::captureFrame() { return texture1_; } +void ftl::gui::Camera::snapshot() { + UNIQUE_LOCK(mutex_, lk); + char timestamp[18]; + std::time_t t = std::time(NULL); + std::strftime(timestamp, sizeof(timestamp), "%F-%H%M%S", std::localtime(&t)); + cv::Mat image; + cv::flip(im1_, image, 0); + cv::imwrite(std::string(timestamp) + ".png", image); +} + +void ftl::gui::Camera::toggleVideoRecording() { + if (recording_) { + src_->removeRawCallback(recorder_); + writer_->end(); + fileout_->close(); + recording_ = false; + } else { + char timestamp[18]; + std::time_t t=std::time(NULL); + std::strftime(timestamp, sizeof(timestamp), "%F-%H%M%S", std::localtime(&t)); + fileout_->open(std::string(timestamp) + ".ftl"); + + writer_->begin(); + src_->addRawCallback(recorder_); + + src_->inject(Channel::Calibration, src_->parameters(), Channel::Left, src_->getCapabilities()); + src_->inject(src_->getPose()); + recording_ = true; + } +} + nlohmann::json ftl::gui::Camera::getMetaData() { return nlohmann::json(); } diff --git a/applications/gui/src/camera.hpp b/applications/gui/src/camera.hpp index 24dcbacfdc51d20166ffc49175f268140e4dcdf3..43cf9c783b1e4b5e3ae003c428b8d6126273ef40 100644 --- a/applications/gui/src/camera.hpp +++ b/applications/gui/src/camera.hpp @@ -2,6 +2,7 @@ #define _FTL_GUI_CAMERA_HPP_ #include <ftl/rgbd/source.hpp> +#include <ftl/codecs/writer.hpp> #include "gltexture.hpp" #include <string> @@ -43,7 +44,7 @@ class Camera { void togglePause(); void isPaused(); - const ftl::codecs::Channels &availableChannels(); + const ftl::codecs::Channels &availableChannels() { return channels_; } const GLTexture &captureFrame(); const GLTexture &getLeft() const { return texture1_; } @@ -51,6 +52,10 @@ class Camera { bool thumbnail(cv::Mat &thumb); + void snapshot(); + + void toggleVideoRecording(); + nlohmann::json getMetaData(); StatisticsImage *stats_ = nullptr; @@ -85,6 +90,10 @@ class Camera { ftl::codecs::Channels channels_; cv::Mat im1_; // first channel (left) cv::Mat im2_; // second channel ("right") + bool recording_; + std::ofstream *fileout_; + ftl::codecs::Writer *writer_; + ftl::rgbd::RawCallback recorder_; MUTEX mutex_; diff --git a/applications/gui/src/config_window.cpp b/applications/gui/src/config_window.cpp index fcba8ff7ad2e033ab790790b03aed4a3af25af15..4832454ad3020f4337def5809bd2f05e2ed83d7e 100644 --- a/applications/gui/src/config_window.cpp +++ b/applications/gui/src/config_window.cpp @@ -2,10 +2,10 @@ #include <nanogui/layout.h> #include <nanogui/label.h> -#include <nanogui/combobox.h> #include <nanogui/button.h> #include <nanogui/entypo.h> #include <nanogui/formhelper.h> +#include <nanogui/vscrollpanel.h> #include <vector> #include <string> @@ -15,28 +15,25 @@ using std::string; using std::vector; using ftl::config::json_t; -ConfigWindow::ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl, const ftl::UUID &peer) : ConfigWindow(parent, ctrl, std::optional<ftl::UUID>(peer)) { - -} - -ConfigWindow::ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl, const std::optional<ftl::UUID> &peer) - : nanogui::Window(parent, "Settings"), ctrl_(ctrl), peer_(peer) { +ConfigWindow::ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl) + : nanogui::Window(parent, "Settings"), ctrl_(ctrl) { using namespace nanogui; setLayout(new GroupLayout()); setPosition(Vector2i(parent->width()/2.0f - 100.0f, parent->height()/2.0f - 100.0f)); //setModal(true); - if (peer) { - configurables_ = ctrl->getConfigurables(peer.value()); - } else { - configurables_ = ftl::config::list(); - } + configurables_ = ftl::config::list(); new Label(this, "Select Configurable","sans-bold"); + auto vscroll = new VScrollPanel(this); + vscroll->setFixedHeight(300); + Widget *buttons = new Widget(vscroll); + buttons->setLayout(new BoxLayout(Orientation::Vertical, Alignment::Fill)); + for (auto c : configurables_) { - auto itembutton = new Button(this, c); + auto itembutton = new Button(buttons, c); itembutton->setCallback([this,c]() { LOG(INFO) << "Change configurable: " << c; _buildForm(c); @@ -52,67 +49,50 @@ ConfigWindow::~ConfigWindow() { } -class ConfigWindow::References { - public: - References(ftl::NetConfigurable* nc, ftl::config::json_t* config, const std::string* suri) : nc(nc), config(config), suri(suri) { - } - - ~References() { - delete nc; - delete config; - delete suri; - } - - private: - ftl::NetConfigurable* nc; - ftl::config::json_t* config; - const std::string* suri; -}; - -std::vector<ftl::gui::ConfigWindow::References *> ConfigWindow::_addElements(nanogui::FormHelper *form, ftl::Configurable &nc, const std::string &suri, std::function<ftl::Configurable*(const std::string*, std::vector<References *>&)> construct) { +void ConfigWindow::_addElements(nanogui::FormHelper *form, const std::string &suri) { using namespace nanogui; - std::vector<References *> references; - - auto data = nc.getConfig(); + Configurable *configurable = ftl::config::find(suri); + ftl::config::json_t data; + if (configurable) { + data = configurable->getConfig(); + } for (auto i=data.begin(); i!=data.end(); ++i) { if (i.key() == "$id") continue; if (i.key() == "$ref" && i.value().is_string()) { LOG(INFO) << "Follow $ref: " << i.value(); - const std::string* suri = new std::string(i.value().get<string>()); - ftl::Configurable* rc = construct(suri, references); - auto new_references = _addElements(form, *rc, *suri, construct); - references.insert(references.end(), new_references.begin(), new_references.end()); + const std::string suri = std::string(i.value().get<string>()); + _addElements(form, suri); continue; } if (i.value().is_boolean()) { string key = i.key(); - form->addVariable<bool>(i.key(), [this,data,key,&nc](const bool &b){ - nc.set(key, b); + form->addVariable<bool>(i.key(), [this,data,key,suri](const bool &b){ + ftl::config::update(suri+"/"+key, b); }, [data,key]() -> bool { return data[key].get<bool>(); }); } else if (i.value().is_number_integer()) { string key = i.key(); - form->addVariable<int>(i.key(), [this,data,key,&nc](const int &f){ - nc.set(key, f); + form->addVariable<int>(i.key(), [this,data,key,suri](const int &f){ + ftl::config::update(suri+"/"+key, f); }, [data,key]() -> int { return data[key].get<int>(); }); } else if (i.value().is_number_float()) { string key = i.key(); - form->addVariable<float>(i.key(), [this,data,key,&nc](const float &f){ - nc.set(key, f); + form->addVariable<float>(i.key(), [this,data,key,suri](const float &f){ + ftl::config::update(suri+"/"+key, f); }, [data,key]() -> float { return data[key].get<float>(); }); } else if (i.value().is_string()) { string key = i.key(); - form->addVariable<string>(i.key(), [this,data,key,&nc](const string &f){ - nc.set(key, f); + form->addVariable<string>(i.key(), [this,data,key,suri](const string &f){ + ftl::config::update(suri+"/"+key, f); }, [data,key]() -> string { return data[key].get<string>(); }); @@ -131,8 +111,6 @@ std::vector<ftl::gui::ConfigWindow::References *> ConfigWindow::_addElements(nan } } } - - return references; } void ConfigWindow::_buildForm(const std::string &suri) { @@ -145,50 +123,15 @@ void ConfigWindow::_buildForm(const std::string &suri) { form->addWindow(Vector2i(100,50), uri.getFragment()); form->window()->setTheme(theme()); - ftl::config::json_t* config; - config = new ftl::config::json_t; - const std::string* allocated_suri = new std::string(suri); - std::vector<ftl::gui::ConfigWindow::References *> references; - - ftl::Configurable* nc; - - if (peer_) { - *config = ctrl_->get(peer_.value(), suri); - nc = new ftl::NetConfigurable(peer_.value(), *allocated_suri, *ctrl_, *config); + _addElements(form, suri); - references = _addElements(form, *nc, *allocated_suri, [this](auto suri, auto &references) { - ftl::config::json_t* config = new ftl::config::json_t; - *config = ctrl_->get(peer_.value(), *suri); - auto nc = new ftl::NetConfigurable(peer_.value(), *suri, *ctrl_, *config); - auto r = new References(nc, config, suri); - references.push_back(r); - return nc; - }); - } else { - nc = ftl::config::find(suri); - if (nc) { - references = _addElements(form, *nc, *allocated_suri, [this](auto suri, auto &references) { - return ftl::config::find(*suri); - }); - } - } - - auto closebutton = form->addButton("Close", [this,form,config,allocated_suri,nc,references]() { + auto closebutton = form->addButton("Close", [this,form]() { form->window()->setVisible(false); - for(auto r : references) { - delete r; - } - if (peer_) { - delete nc; - } - delete config; - delete allocated_suri; delete form; }); closebutton->setIcon(ENTYPO_ICON_CROSS); } bool ConfigWindow::exists(const std::string &uri) { - // If the Configurable is a NetConfigurable, the URI is not checked. - return peer_ || ftl::config::find(uri); -} \ No newline at end of file + return ftl::config::find(uri) != nullptr; +} diff --git a/applications/gui/src/config_window.hpp b/applications/gui/src/config_window.hpp index 23279d93cee1d601e53e0147b4edee8d5309a483..a0fe74155fe5320f983871d8c9237c7571625670 100644 --- a/applications/gui/src/config_window.hpp +++ b/applications/gui/src/config_window.hpp @@ -16,23 +16,15 @@ namespace gui { */ class ConfigWindow : public nanogui::Window { public: - ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl, const ftl::UUID &peer); - ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl, const std::optional<ftl::UUID> &peer = std::nullopt); + ConfigWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl); ~ConfigWindow(); private: - /* - References holds the pointers to a NetConfigurable and all its members so that - they can all be returned from _addElements() and then simultaneously deleted - as the form is closed. - */ - class References; ftl::ctrl::Master *ctrl_; - std::optional<ftl::UUID> peer_; std::vector<std::string> configurables_; void _buildForm(const std::string &uri); - std::vector<References *> _addElements(nanogui::FormHelper *form, ftl::Configurable &nc, const std::string &suri, std::function<ftl::Configurable*(const std::string*, std::vector<References *>&)> construct); + void _addElements(nanogui::FormHelper *form, const std::string &suri); bool exists(const std::string &uri); }; diff --git a/applications/gui/src/ctrl_window.cpp b/applications/gui/src/ctrl_window.cpp index 67a3682bd2fcfcb55a68fb9c71b6dd55aad36491..fc82c45838a568efc8b4e8d456cdb3fbbef2c8b4 100644 --- a/applications/gui/src/ctrl_window.cpp +++ b/applications/gui/src/ctrl_window.cpp @@ -69,7 +69,7 @@ ControlWindow::ControlWindow(nanogui::Widget *parent, ftl::ctrl::Master *ctrl) button = new Button(tools, "", ENTYPO_ICON_COG); button->setCallback([this,parent] { - auto cfgwin = new ConfigWindow(parent, ctrl_, _getActiveID()); + auto cfgwin = new ConfigWindow(parent, ctrl_); cfgwin->setTheme(theme()); }); button->setTooltip("Edit node configuration"); diff --git a/applications/gui/src/main.cpp b/applications/gui/src/main.cpp index 50bc3638c2e26197fbcf5b74dadacd4b6a49d0ad..7875e52bb04afc59953ac1a728dafe64008b6d6c 100644 --- a/applications/gui/src/main.cpp +++ b/applications/gui/src/main.cpp @@ -2,6 +2,7 @@ #include <ftl/net/universe.hpp> #include <ftl/rgbd.hpp> #include <ftl/master.hpp> +#include <ftl/net_configurable.hpp> #include <loguru.hpp> @@ -12,9 +13,6 @@ int main(int argc, char **argv) { auto root = ftl::configure(argc, argv, "gui_default"); ftl::net::Universe *net = ftl::create<ftl::net::Universe>(root, "net"); - net->start(); - net->waitConnections(); - ftl::ctrl::Master *controller = new ftl::ctrl::Master(root, net); controller->onLog([](const ftl::ctrl::LogEvent &e){ const int v = e.verbosity; @@ -25,6 +23,33 @@ int main(int argc, char **argv) { } }); + std::map<ftl::UUID, std::vector<ftl::NetConfigurable*>> peerConfigurables; + + net->onConnect([&controller, &peerConfigurables](ftl::net::Peer *p) { + ftl::UUID peer = p->id(); + auto cs = controller->getConfigurables(peer); + for (auto c : cs) { + ftl::config::json_t *configuration = new ftl::config::json_t; + *configuration = controller->get(peer, c); + if (!configuration->empty()) { + ftl::NetConfigurable *nc = new ftl::NetConfigurable(peer, c, *controller, *configuration); + peerConfigurables[peer].push_back(nc); + } + } + }); + + net->onDisconnect([&peerConfigurables](ftl::net::Peer *p) { + ftl::UUID peer = p->id(); + for (ftl::NetConfigurable *nc : peerConfigurables[peer]) { + ftl::config::json_t *configuration = &(nc->getConfig()); + delete nc; + delete configuration; + } + }); + + net->start(); + net->waitConnections(); + /*auto available = net.findAll<string>("list_streams"); for (auto &a : available) { std::cout << " -- " << a << std::endl; @@ -57,4 +82,4 @@ int main(int argc, char **argv) { delete root; return 0; -} \ No newline at end of file +} diff --git a/applications/gui/src/media_panel.cpp b/applications/gui/src/media_panel.cpp index 800940199e2488ca1b11bd723498059efd63d374..c04552fcd2207971e12e9b8e49a04491629ea63f 100644 --- a/applications/gui/src/media_panel.cpp +++ b/applications/gui/src/media_panel.cpp @@ -1,6 +1,5 @@ #include "media_panel.hpp" #include "screen.hpp" -#include "camera.hpp" #include <nanogui/layout.h> #include <nanogui/button.h> @@ -18,7 +17,6 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""), using namespace nanogui; paused_ = false; - writer_ = nullptr; disable_switch_channels_ = false; setLayout(new BoxLayout(Orientation::Horizontal, @@ -35,29 +33,62 @@ MediaPanel::MediaPanel(ftl::gui::Screen *screen) : nanogui::Window(screen, ""), if (cam) cam->showPoseWindow(); }); - button = new Button(this, "", ENTYPO_ICON_CONTROLLER_RECORD); - button->setFlags(Button::ToggleButton); - button->setChangeCallback([this,button](bool state) { - if (state){ - auto *cam = screen_->activeCamera(); - - button->setTextColor(nanogui::Color(1.0f,0.1f,0.1f,1.0f)); - char timestamp[18]; - std::time_t t=std::time(NULL); - std::strftime(timestamp, sizeof(timestamp), "%F-%H%M%S", std::localtime(&t)); - writer_ = new ftl::rgbd::SnapshotStreamWriter(std::string(timestamp) + ".tar.gz", 1000 / 25); - writer_->addSource(cam->source()); - writer_->start(); - } else { - button->setTextColor(nanogui::Color(1.0f,1.0f,1.0f,1.0f)); - if (writer_) { - writer_->stop(); - delete writer_; - writer_ = nullptr; + virtualCameraRecording_ = std::optional<ftl::gui::Camera*>(); + sceneRecording_ = std::optional<ftl::Configurable*>(); + + auto recordbutton = new PopupButton(this, "", ENTYPO_ICON_CONTROLLER_RECORD); + recordbutton->setTooltip("Record"); + recordbutton->setSide(Popup::Side::Right); + recordbutton->setChevronIcon(0); + auto recordpopup = recordbutton->popup(); + recordpopup->setLayout(new GroupLayout()); + recordpopup->setTheme(screen->toolbuttheme); + recordpopup->setAnchorHeight(150); + auto itembutton = new Button(recordpopup, "2D snapshot (.png)"); + itembutton->setCallback([this,recordbutton]() { + screen_->activeCamera()->snapshot(); + recordbutton->setPushed(false); + }); + itembutton = new Button(recordpopup, "Virtual camera recording (.ftl)"); + itembutton->setCallback([this,recordbutton]() { + auto activeCamera = screen_->activeCamera(); + activeCamera->toggleVideoRecording(); + recordbutton->setTextColor(nanogui::Color(1.0f,0.1f,0.1f,1.0f)); + recordbutton->setPushed(false); + virtualCameraRecording_ = std::optional<ftl::gui::Camera*>(activeCamera); + }); + itembutton = new Button(recordpopup, "3D scene recording (.ftl)"); + itembutton->setCallback([this,recordbutton]() { + auto tag = screen_->activeCamera()->source()->get<std::string>("uri"); + if (tag) { + auto tagvalue = tag.value(); + auto configurables = ftl::config::findByTag(tagvalue); + if (configurables.size() > 0) { + ftl::Configurable *configurable = configurables[0]; + configurable->set("record", true); + recordbutton->setTextColor(nanogui::Color(1.0f,0.1f,0.1f,1.0f)); + sceneRecording_ = std::optional<ftl::Configurable*>(configurable); } } - //if (state) ... start - //else ... stop + recordbutton->setPushed(false); + }); + itembutton = new Button(recordpopup, "Detailed recording options"); + + recordbutton->setCallback([this,recordbutton](){ + if (virtualCameraRecording_) { + virtualCameraRecording_.value()->toggleVideoRecording(); + recordbutton->setTextColor(nanogui::Color(1.0f,1.0f,1.0f,1.0f)); + + // Prevents the popup from being opened, though it is shown while the button + // is being pressed. + recordbutton->setPushed(false); + virtualCameraRecording_ = std::nullopt; + } else if (sceneRecording_) { + sceneRecording_.value()->set("record", false); + recordbutton->setTextColor(nanogui::Color(1.0f,1.0f,1.0f,1.0f)); + recordbutton->setPushed(false); + sceneRecording_ = std::nullopt; + } }); button = new Button(this, "", ENTYPO_ICON_CONTROLLER_STOP); diff --git a/applications/gui/src/media_panel.hpp b/applications/gui/src/media_panel.hpp index 0279cb3fadab41003ceefef538e8f42a20f00139..df0b0802294cbe64800c850faa60fadf4f3de55b 100644 --- a/applications/gui/src/media_panel.hpp +++ b/applications/gui/src/media_panel.hpp @@ -1,6 +1,8 @@ #ifndef _FTL_GUI_MEDIAPANEL_HPP_ #define _FTL_GUI_MEDIAPANEL_HPP_ +#include "camera.hpp" + #include <nanogui/window.h> namespace ftl { @@ -30,6 +32,15 @@ class MediaPanel : public nanogui::Window { nanogui::PopupButton *button_channels_; nanogui::Button *right_button_; nanogui::Button *depth_button_; + + /** + * These members indicate which type of recording is active, if any. + * They also include a pointer to an object which is used + * to end the recording. Only one of these members should have a value + * at any given time. + */ + std::optional<ftl::gui::Camera*> virtualCameraRecording_; + std::optional<ftl::Configurable*> sceneRecording_; }; } diff --git a/applications/gui/src/screen.cpp b/applications/gui/src/screen.cpp index 2dbfd2d54c4b1f30f17dc0e0e26274d986286ad3..cdc6934f117b0372f007a506addbe8256ab3627c 100644 --- a/applications/gui/src/screen.cpp +++ b/applications/gui/src/screen.cpp @@ -6,7 +6,6 @@ #include <nanogui/window.h> #include <nanogui/layout.h> #include <nanogui/imageview.h> -#include <nanogui/combobox.h> #include <nanogui/label.h> #include <nanogui/toolbutton.h> #include <nanogui/popupbutton.h> @@ -231,30 +230,29 @@ ftl::gui::Screen::Screen(ftl::Configurable *proot, ftl::net::Universe *pnet, ftl popup->setVisible(false); }); - popbutton = new PopupButton(innertool, "", ENTYPO_ICON_COG); - popbutton->setIconExtraScale(1.5f); - popbutton->setTheme(toolbuttheme); - popbutton->setTooltip("Settings"); - popbutton->setFixedSize(Vector2i(40,40)); - popbutton->setSide(Popup::Side::Right); - popbutton->setChevronIcon(0); - // popbutton->setPosition(Vector2i(5,height()-50)); - popup = popbutton->popup(); - popup->setLayout(new GroupLayout()); - popup->setTheme(toolbuttheme); + itembutton = new Button(innertool, "", ENTYPO_ICON_COG); + itembutton->setIconExtraScale(1.5f); + itembutton->setTheme(toolbuttheme); + itembutton->setTooltip("Settings"); + itembutton->setFixedSize(Vector2i(40,40)); + + itembutton->setCallback([this]() { + auto config_window = new ConfigWindow(this, ctrl_); + config_window->setTheme(windowtheme); + }); + /* //net_->onConnect([this,popup](ftl::net::Peer *p) { { LOG(INFO) << "NET CONNECT"; auto node_details = ctrl_->getSlaves(); - std::vector<std::string> node_titles; for (auto &d : node_details) { LOG(INFO) << "ADDING TITLE: " << d.dump(); 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); + auto config_window = new ConfigWindow(this, ctrl_); config_window->setTheme(windowtheme); }); } @@ -266,6 +264,7 @@ ftl::gui::Screen::Screen(ftl::Configurable *proot, ftl::net::Universe *pnet, ftl auto config_window = new ConfigWindow(this, ctrl_); config_window->setTheme(windowtheme); }); + */ //configwindow_ = new ConfigWindow(parent, ctrl_); cwindow_ = new ftl::gui::ControlWindow(this, controller); diff --git a/applications/gui/src/src_window.cpp b/applications/gui/src/src_window.cpp index 8e087d1dd42e25b00afd0efaf7b5dd22d5139a0d..0126810a511b85a1168fe06c638651e533f11a0d 100644 --- a/applications/gui/src/src_window.cpp +++ b/applications/gui/src/src_window.cpp @@ -63,7 +63,7 @@ SourceWindow::SourceWindow(ftl::gui::Screen *screen) UNIQUE_LOCK(mutex_, lk); _updateCameras(screen_->net()->findAll<string>("list_streams")); }); - + UNIQUE_LOCK(mutex_, lk); std::vector<ftl::rgbd::Source*> srcs = ftl::createArray<ftl::rgbd::Source>(screen_->root(), "sources", screen_->net()); @@ -74,6 +74,14 @@ SourceWindow::SourceWindow(ftl::gui::Screen *screen) _updateCameras(screen_->control()->getNet()->findAll<string>("list_streams")); } +std::vector<ftl::gui::Camera*> SourceWindow::getCameras() { + auto cameras = std::vector<ftl::gui::Camera*>(cameras_.size()); + for (const auto &kv : cameras_) { + cameras.push_back(kv.second); + } + return cameras; +} + void SourceWindow::_updateCameras(const vector<string> &netcams) { for (auto s : netcams) { if (cameras_.find(s) == cameras_.end()) { diff --git a/applications/gui/src/src_window.hpp b/applications/gui/src/src_window.hpp index b2fe8a9e0957f3345a719a0c37bac46bf473089c..dab3f5d4301de73d0dda2bbd32b321c3f796d160 100644 --- a/applications/gui/src/src_window.hpp +++ b/applications/gui/src/src_window.hpp @@ -25,7 +25,7 @@ class SourceWindow : public nanogui::Window { explicit SourceWindow(ftl::gui::Screen *screen); ~SourceWindow(); - const std::vector<ftl::gui::Camera*> &getCameras(); + std::vector<ftl::gui::Camera*> getCameras(); virtual void draw(NVGcontext *ctx); diff --git a/applications/reconstruct/src/ilw/ilw.cpp b/applications/reconstruct/src/ilw/ilw.cpp index 55a9539a9cc9766bf49849164099ee5f620c4c8d..a686f35c337573a04415b0f13a598ec8a3538057 100644 --- a/applications/reconstruct/src/ilw/ilw.cpp +++ b/applications/reconstruct/src/ilw/ilw.cpp @@ -25,7 +25,7 @@ static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) { } ILW::ILW(nlohmann::json &config) : ftl::Configurable(config) { - enabled_ = value("ilw_align", true); + enabled_ = value("ilw_align", false); iterations_ = value("iterations", 4); motion_rate_ = value("motion_rate", 0.8f); motion_window_ = value("motion_window", 3); @@ -42,7 +42,7 @@ ILW::ILW(nlohmann::json &config) : ftl::Configurable(config) { }); on("ilw_align", [this](const ftl::config::Event &e) { - enabled_ = value("ilw_align", true); + enabled_ = value("ilw_align", false); }); on("iterations", [this](const ftl::config::Event &e) { diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp index 3db5d6603fad4dc7b93106d3974dcec8d8ff9704..551a2dfe309bf8a5a29c17cc4856acb48f70f09c 100644 --- a/applications/reconstruct/src/main.cpp +++ b/applications/reconstruct/src/main.cpp @@ -37,6 +37,8 @@ #include <ftl/operators/segmentation.hpp> #include <ftl/operators/mask.hpp> #include <ftl/operators/antialiasing.hpp> +#include <ftl/operators/mvmls.hpp> +#include <ftl/operators/clipping.hpp> #include <ftl/cuda/normals.hpp> #include <ftl/registration.hpp> @@ -75,8 +77,10 @@ static Eigen::Affine3d create_rotation_matrix(float ax, float ay, float az) { return rz * rx * ry; } -// TODO: Remove this class (requires more general solution). Also does not -// process disconnections/reconnections/types etc. correctly. +// TODO: * Remove this class (requires more general solution). Also does not +// process disconnections/reconnections/types etc. correctly. +// * Update when new options become available. + class ConfigProxy { private: vector<ftl::UUID> peers_; @@ -99,20 +103,25 @@ class ConfigProxy { auto config = json_t::parse(net_->call<string>(peers_[0], "get_cfg", uris_[0] + "/" + uri)); auto *proxy = ftl::create<ftl::Configurable>(root, name); - for (auto &itm : config.get<json::object_t>()) { - auto key = itm.first; - auto value = itm.second; - if (*key.begin() == '$') { continue; } - - proxy->set(key, value); - proxy->on(key, [this, uri, key, value, proxy](const ftl::config::Event&) { - for (size_t i = 0; i < uris_.size(); i++) { - // TODO: check that config exists? - auto peer = peers_[i]; - std::string name = uris_[i] + "/" + uri + "/" + key; - net_->send(peer, "update_cfg", name, proxy->getConfig()[key].dump()); - } - }); + try { + for (auto &itm : config.get<json::object_t>()) { + auto key = itm.first; + auto value = itm.second; + if (*key.begin() == '$') { continue; } + + proxy->set(key, value); + proxy->on(key, [this, uri, key, value, proxy](const ftl::config::Event&) { + for (size_t i = 0; i < uris_.size(); i++) { + // TODO: check that config exists? + auto peer = peers_[i]; + std::string name = uris_[i] + "/" + uri + "/" + key; + net_->send(peer, "update_cfg", name, proxy->getConfig()[key].dump()); + } + }); + } + } + catch (nlohmann::detail::type_error) { + LOG(ERROR) << "Failed to add config proxy for: " << uri << "/" << name; } } }; @@ -166,7 +175,7 @@ static void run(ftl::Configurable *root) { LOG(ERROR) << "No sources configured!"; return; } - + ConfigProxy *configproxy = nullptr; if (net->numberOfPeers() > 0) { configproxy = new ConfigProxy(net); // TODO delete @@ -174,6 +183,8 @@ static void run(ftl::Configurable *root) { 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"); + configproxy->add(disparity, "source/disparity/mls", "mls"); + configproxy->add(disparity, "source/disparity/cross", "cross"); } // Create scene transform, intended for axis aligning the walls and floor @@ -230,6 +241,7 @@ static void run(ftl::Configurable *root) { //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::VirtualSource *virt = ftl::create<ftl::rgbd::VirtualSource>(root, "virtual"); + root->set("tags", nlohmann::json::array({ root->getID()+"/virtual" })); ftl::render::Triangular *splat = ftl::create<ftl::render::Triangular>(root, "renderer", &scene_B); ftl::rgbd::Group *group = new ftl::rgbd::Group; ftl::ILW *align = ftl::create<ftl::ILW>(root, "merge"); @@ -289,7 +301,7 @@ static void run(ftl::Configurable *root) { // TODO: Write pose+calibration+config packets auto sources = group->sources(); - for (int i=0; i<sources.size(); ++i) { + for (size_t i=0; i<sources.size(); ++i) { //writeSourceProperties(writer, i, sources[i]); sources[i]->inject(Channel::Calibration, sources[i]->parameters(), Channel::Left, sources[i]->getCapabilities()); sources[i]->inject(sources[i]->getPose()); @@ -311,6 +323,7 @@ static void run(ftl::Configurable *root) { // Create the source depth map pipeline 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::HFSmoother>("hfnoise"); // Remove high-frequency noise pipeline1->append<ftl::operators::Normals>("normals"); // Estimate surface normals @@ -319,8 +332,9 @@ static void run(ftl::Configurable *root) { pipeline1->append<ftl::operators::CrossSupport>("cross"); pipeline1->append<ftl::operators::DiscontinuityMask>("discontinuity"); pipeline1->append<ftl::operators::CullDiscontinuity>("remove_discontinuity"); - pipeline1->append<ftl::operators::AggreMLS>("mls"); // Perform MLS (using smoothing channel) + //pipeline1->append<ftl::operators::AggreMLS>("mls"); // Perform MLS (using smoothing channel) pipeline1->append<ftl::operators::VisCrossSupport>("viscross")->set("enabled", false); + pipeline1->append<ftl::operators::MultiViewMLS>("mvmls"); // Alignment diff --git a/components/common/cpp/include/ftl/configuration.hpp b/components/common/cpp/include/ftl/configuration.hpp index 94fcc7dfa6b57e9bfd59fbcf36c5be80e0b82638..9e4ba8aed4bcf8b5f2c8cec2c1079edb945359c3 100644 --- a/components/common/cpp/include/ftl/configuration.hpp +++ b/components/common/cpp/include/ftl/configuration.hpp @@ -72,6 +72,13 @@ json_t &resolveWait(const std::string &); */ Configurable *find(const std::string &uri); +/** + * Get all configurables that contain a specified tag. Tags are given under the + * "tags" property as an array of strings, but only during configurable + * construction. + */ +const std::vector<Configurable *> &findByTag(const std::string &tag); + std::vector<std::string> list(); /** diff --git a/components/common/cpp/src/configuration.cpp b/components/common/cpp/src/configuration.cpp index bd9d9feec20538cebc210cafba72a98f651b243c..aa236c8a06772e71d59edd3886ce7a9cb14e2eec 100644 --- a/components/common/cpp/src/configuration.cpp +++ b/components/common/cpp/src/configuration.cpp @@ -165,6 +165,7 @@ static bool mergeConfig(const string path) { static std::map<std::string, json_t*> config_index; static std::map<std::string, ftl::Configurable*> config_instance; +static std::map<std::string, std::vector<ftl::Configurable*>> tag_index; /* * Recursively URI index the JSON structure. @@ -198,6 +199,10 @@ ftl::Configurable *ftl::config::find(const std::string &uri) { else return (*ix).second; } +const std::vector<Configurable*> &ftl::config::findByTag(const std::string &tag) { + return tag_index[tag]; +} + std::vector<std::string> ftl::config::list() { vector<string> r; for (auto i : config_instance) { @@ -219,6 +224,13 @@ void ftl::config::registerConfigurable(ftl::Configurable *cfg) { } else { config_instance[*uri] = cfg; LOG(INFO) << "Registering instance: " << *uri; + + auto tags = cfg->get<vector<string>>("tags"); + if (tags) { + for (auto &t : *tags) { + tag_index[t].push_back(cfg); + } + } } } @@ -290,7 +302,8 @@ json_t &ftl::config::resolve(const std::string &puri, bool eager) { std::string u = uri.getBaseURI(); auto ix = config_index.find(u); if (ix == config_index.end()) { - LOG(FATAL) << "Cannot find resource: " << u; + LOG(WARNING) << "Cannot find resource: " << u; + return null_json; } auto ptr = nlohmann::json::json_pointer("/"+uri.getFragment()); diff --git a/components/net/cpp/include/ftl/net_configurable.hpp b/components/net/cpp/include/ftl/net_configurable.hpp index bdd21c4700e7664cff996672585054c30b6e8e6a..d9fd6e5288758de51de91bce65a1afd86831f19e 100644 --- a/components/net/cpp/include/ftl/net_configurable.hpp +++ b/components/net/cpp/include/ftl/net_configurable.hpp @@ -17,7 +17,7 @@ namespace ftl { private: ftl::UUID peer; - const std::string &suri; + const std::string suri; ftl::ctrl::Master &ctrl; }; diff --git a/components/operators/CMakeLists.txt b/components/operators/CMakeLists.txt index f177aa59124c5e08a0321712ace7e9528eb3d7db..b025a39b357a628ee84d2f6d3d7b82c8aa6fcc3e 100644 --- a/components/operators/CMakeLists.txt +++ b/components/operators/CMakeLists.txt @@ -10,7 +10,6 @@ set(OPERSRC src/filling.cu 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 @@ -18,8 +17,16 @@ set(OPERSRC src/mask.cpp src/antialiasing.cpp src/antialiasing.cu + src/mvmls.cpp + src/correspondence.cu + src/clipping.cpp ) + +if (LIBSGM_FOUND) + list(APPEND OPERSRC src/disparity/fixstars_sgm.cpp) +endif (LIBSGM_FOUND) + if (HAVE_OPTFLOW) list(APPEND OPERSRC src/nvopticalflow.cpp diff --git a/components/operators/include/ftl/operators/clipping.hpp b/components/operators/include/ftl/operators/clipping.hpp new file mode 100644 index 0000000000000000000000000000000000000000..590e714c9eeca9713e56139aa874f7c0db0a472d --- /dev/null +++ b/components/operators/include/ftl/operators/clipping.hpp @@ -0,0 +1,27 @@ +#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_ diff --git a/components/operators/include/ftl/operators/disparity.hpp b/components/operators/include/ftl/operators/disparity.hpp index fa280871d15912a2eee8c384f0535ebbdfdcbc47..0c26c904fbfa8e2dce0d209347b612f6bb719b63 100644 --- a/components/operators/include/ftl/operators/disparity.hpp +++ b/components/operators/include/ftl/operators/disparity.hpp @@ -7,16 +7,18 @@ #include <opencv2/cudaoptflow.hpp> #endif +#ifdef HAVE_LIBSGM #include <libsgm.h> +#endif namespace ftl { namespace operators { +#ifdef HAVE_LIBSGM /* * FixstarsSGM https://github.com/fixstars/libSGM * * Requires modified version https://gitlab.utu.fi/joseha/libsgm - * */ class FixstarsSGM : public ftl::operators::Operator { public: @@ -41,6 +43,7 @@ class FixstarsSGM : public ftl::operators::Operator { int max_disp_; float uniqueness_; }; +#endif class DisparityBilateralFilter : public::ftl::operators::Operator { public: diff --git a/components/operators/include/ftl/operators/mask.hpp b/components/operators/include/ftl/operators/mask.hpp index ef9758e39bea32a07498b32f76fdb67810fe6cfa..579b1f6fe83daf7402041fe139116abe09ee3234 100644 --- a/components/operators/include/ftl/operators/mask.hpp +++ b/components/operators/include/ftl/operators/mask.hpp @@ -14,12 +14,12 @@ namespace operators { */ class DiscontinuityMask : public ftl::operators::Operator { public: - explicit DiscontinuityMask(ftl::Configurable*); - ~DiscontinuityMask(); + explicit DiscontinuityMask(ftl::Configurable*); + ~DiscontinuityMask(); 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; + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; }; @@ -28,12 +28,12 @@ class DiscontinuityMask : public ftl::operators::Operator { */ class CullDiscontinuity : public ftl::operators::Operator { public: - explicit CullDiscontinuity(ftl::Configurable*); - ~CullDiscontinuity(); + explicit CullDiscontinuity(ftl::Configurable*); + ~CullDiscontinuity(); 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; + bool apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Source *src, cudaStream_t stream) override; }; diff --git a/components/operators/include/ftl/operators/mvmls.hpp b/components/operators/include/ftl/operators/mvmls.hpp new file mode 100644 index 0000000000000000000000000000000000000000..6b8eff1be304693cfe7dee96152f9aa4cd3452b4 --- /dev/null +++ b/components/operators/include/ftl/operators/mvmls.hpp @@ -0,0 +1,28 @@ +#ifndef _FTL_OPERATORS_MVMLS_HPP_ +#define _FTL_OPERATORS_MVMLS_HPP_ + +#include <ftl/operators/operator.hpp> + +namespace ftl { +namespace operators { + +class MultiViewMLS : public ftl::operators::Operator { + public: + explicit MultiViewMLS(ftl::Configurable*); + ~MultiViewMLS(); + + inline Operator::Type type() const override { return Operator::Type::ManyToMany; } + + bool apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream) override; + + private: + std::vector<ftl::cuda::TextureObject<float4>> centroid_horiz_; + std::vector<ftl::cuda::TextureObject<float4>> centroid_vert_; + std::vector<ftl::cuda::TextureObject<float4>> normals_horiz_; + std::vector<ftl::cuda::TextureObject<float>> contributions_; +}; + +} +} + +#endif diff --git a/components/operators/src/clipping.cpp b/components/operators/src/clipping.cpp new file mode 100644 index 0000000000000000000000000000000000000000..b37abe2c33b55b86b697565d1565b523c073d80f --- /dev/null +++ b/components/operators/src/clipping.cpp @@ -0,0 +1,60 @@ +#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; +} diff --git a/components/operators/src/correspondence.cu b/components/operators/src/correspondence.cu new file mode 100644 index 0000000000000000000000000000000000000000..36e91d9f483d62164b284f43b82443641eadd664 --- /dev/null +++ b/components/operators/src/correspondence.cu @@ -0,0 +1,548 @@ +#include "mvmls_cuda.hpp" +#include <ftl/cuda/weighting.hpp> +#include <ftl/cuda/mask.hpp> + +using ftl::cuda::TextureObject; +using ftl::rgbd::Camera; +using ftl::cuda::Mask; +using ftl::cuda::MvMLSParams; + +#define T_PER_BLOCK 8 + +template<int FUNCTION> +__device__ float weightFunction(const ftl::cuda::MvMLSParams ¶ms, float dweight, float cweight); + +template <> +__device__ inline float weightFunction<0>(const ftl::cuda::MvMLSParams ¶ms, float dweight, float cweight) { + return (params.cost_ratio * (cweight) + (1.0f - params.cost_ratio) * dweight); +} + +template <> +__device__ inline float weightFunction<1>(const ftl::cuda::MvMLSParams ¶m, float dweight, float cweight) { + return (cweight * cweight * dweight); +} + +template <> +__device__ inline float weightFunction<2>(const ftl::cuda::MvMLSParams ¶m, float dweight, float cweight) { + return (dweight * dweight * cweight); +} + +template <> +__device__ inline float weightFunction<3>(const ftl::cuda::MvMLSParams ¶ms, float dweight, float cweight) { + return (dweight == 0.0f) ? 0.0f : (params.cost_ratio * (cweight) + (1.0f - params.cost_ratio) * dweight); +} + +template <> +__device__ inline float weightFunction<4>(const ftl::cuda::MvMLSParams ¶ms, float dweight, float cweight) { + return cweight; +} + +template <> +__device__ inline float weightFunction<5>(const ftl::cuda::MvMLSParams ¶ms, float dweight, float cweight) { + return (cweight > 0.0f) ? dweight : 0.0f; +} + +template<int COR_STEPS, int FUNCTION> +__global__ void corresponding_point_kernel( + TextureObject<float> d1, + TextureObject<float> d2, + TextureObject<uchar4> c1, + TextureObject<uchar4> c2, + TextureObject<short2> screenOut, + TextureObject<float> conf, + TextureObject<int> mask, + float4x4 pose1, + float4x4 pose1_inv, + float4x4 pose2, // Inverse + Camera cam1, + Camera cam2, ftl::cuda::MvMLSParams params) { + + // Each warp picks point in p1 + //const int tid = (threadIdx.x + threadIdx.y * blockDim.x); + const int x = (blockIdx.x*blockDim.x + threadIdx.x); // / WARP_SIZE; + const int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x >= 0 && y >=0 && x < screenOut.width() && y < screenOut.height()) { + screenOut(x,y) = make_short2(-1,-1); + + //const float3 world1 = make_float3(p1.tex2D(x, y)); + const float depth1 = d1.tex2D(x,y); //(pose1_inv * world1).z; // Initial starting depth + if (depth1 < cam1.minDepth || depth1 > cam1.maxDepth) return; + + // TODO: Temporary hack to ensure depth1 is present + //const float4 temp = vout.tex2D(x,y); + //vout(x,y) = make_float4(depth1, 0.0f, temp.z, temp.w); + + const float3 world1 = pose1 * cam1.screenToCam(x,y,depth1); + + const auto colour1 = c1.tex2D((float)x+0.5f, (float)y+0.5f); + + //float bestdepth = 0.0f; + short2 bestScreen = make_short2(-1,-1); + float bestdepth = 0.0f; + float bestdepth2 = 0.0f; + float bestweight = 0.0f; + float bestcolour = 0.0f; + float bestdweight = 0.0f; + float totalcolour = 0.0f; + int count = 0; + float contrib = 0.0f; + + const float step_interval = params.range / (COR_STEPS / 2); + + const float3 rayStep_world = pose1.getFloat3x3() * cam1.screenToCam(x,y,step_interval); + const float3 rayStart_2 = pose2 * world1; + const float3 rayStep_2 = pose2.getFloat3x3() * rayStep_world; + + // Project to p2 using cam2 + // Each thread takes a possible correspondence and calculates a weighting + //const int lane = tid % WARP_SIZE; + for (int i=0; i<COR_STEPS; ++i) { + const int j = i - (COR_STEPS/2); + const float depth_adjust = (float)j * step_interval; + + // Calculate adjusted depth 3D point in camera 2 space + const float3 worldPos = world1 + j * rayStep_world; //(pose1 * cam1.screenToCam(x, y, depth_adjust)); + const float3 camPos = rayStart_2 + j * rayStep_2; //pose2 * worldPos; + const float2 screen = cam2.camToScreen<float2>(camPos); + + float weight = (screen.x >= cam2.width || screen.y >= cam2.height) ? 0.0f : 1.0f; + + // Generate a colour correspondence value + const auto colour2 = c2.tex2D(screen.x, screen.y); + const float cweight = ftl::cuda::colourWeighting(colour1, colour2, params.colour_smooth); + + // Generate a depth correspondence value + const float depth2 = d2.tex2D(int(screen.x+0.5f), int(screen.y+0.5f)); + + if (FUNCTION == 1) { + weight *= ftl::cuda::weighting(fabs(depth2 - camPos.z), cweight*params.spatial_smooth); + } else { + const float dweight = ftl::cuda::weighting(fabs(depth2 - camPos.z), params.spatial_smooth); + weight *= weightFunction<FUNCTION>(params, dweight, cweight); + } + //const float dweight = ftl::cuda::weighting(fabs(depth_adjust), 10.0f*params.range); + + //weight *= weightFunction<FUNCTION>(params, dweight, cweight); + + ++count; + contrib += weight; + bestcolour = max(cweight, bestcolour); + //bestdweight = max(dweight, bestdweight); + totalcolour += cweight; + bestdepth = (weight > bestweight) ? depth_adjust : bestdepth; + //bestdepth2 = (weight > bestweight) ? camPos.z : bestdepth2; + //bestScreen = (weight > bestweight) ? make_short2(screen.x+0.5f, screen.y+0.5f) : bestScreen; + bestweight = max(bestweight, weight); + //bestweight = weight; + //bestdepth = depth_adjust; + //bestScreen = make_short2(screen.x+0.5f, screen.y+0.5f); + //} + } + + const float avgcolour = totalcolour/(float)count; + const float confidence = bestcolour / totalcolour; //bestcolour - avgcolour; + + //Mask m(mask.tex2D(x,y)); + + //if (bestweight > 0.0f) { + float old = conf.tex2D(x,y); + + if (bestweight * confidence > old) { + d1(x,y) = 0.4f*bestdepth + depth1; + //d2(bestScreen.x, bestScreen.y) = bestdepth2; + //screenOut(x,y) = bestScreen; + conf(x,y) = bestweight * confidence; + } + //} + + // If a good enough match is found, mark dodgy depth as solid + //if ((m.isFilled() || m.isDiscontinuity()) && (bestweight > params.match_threshold)) mask(x,y) = 0; + } +} + +void ftl::cuda::correspondence( + TextureObject<float> &d1, + TextureObject<float> &d2, + TextureObject<uchar4> &c1, + TextureObject<uchar4> &c2, + TextureObject<short2> &screen, + TextureObject<float> &conf, + TextureObject<int> &mask, + float4x4 &pose1, + float4x4 &pose1_inv, + float4x4 &pose2, + const Camera &cam1, + const Camera &cam2, const MvMLSParams ¶ms, int func, + cudaStream_t stream) { + + const dim3 gridSize((d1.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (d1.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + //printf("COR SIZE %d,%d\n", p1.width(), p1.height()); + + switch (func) { + case 0: corresponding_point_kernel<16,0><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + case 1: corresponding_point_kernel<16,1><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + case 2: corresponding_point_kernel<16,2><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + case 3: corresponding_point_kernel<16,3><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + case 4: corresponding_point_kernel<16,4><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + case 5: corresponding_point_kernel<16,5><<<gridSize, blockSize, 0, stream>>>(d1, d2, c1, c2, screen, conf, mask, pose1, pose1_inv, pose2, cam1, cam2, params); break; + } + + cudaSafeCall( cudaGetLastError() ); +} + +// ==== Remove zero-confidence ================================================= + +__global__ void zero_confidence_kernel( + TextureObject<float> conf, + TextureObject<float> depth) { + + const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; + const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x < depth.width() && y < depth.height()) { + const float c = conf.tex2D((int)x,(int)y); + + if (c == 0.0f) { + depth(x,y) = 1000.0f; + } + } +} + +void ftl::cuda::zero_confidence(TextureObject<float> &conf, TextureObject<float> &depth, 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); + + zero_confidence_kernel<<<gridSize, blockSize, 0, stream>>>(conf, depth); + cudaSafeCall( cudaGetLastError() ); +} + + +// ==== MultiViewMLS Aggregate ================================================= + +__device__ inline short3 getScreenPos(int x, int y, float d, const Camera &cam1, const Camera &cam2, const float4x4 &transform) { + const float3 campos = transform * cam1.screenToCam(x,y,d); + const int2 screen = cam2.camToScreen<int2>(campos); + return make_short3(screen.x, screen.y, campos.z); +} + +__device__ inline short2 packScreen(int x, int y, int id) { + return make_short2((id << 12) + x, y); +} + +__device__ inline short2 packScreen(const short3 &p, int id) { + return make_short2((id << 12) + p.x, p.y); +} + +__device__ inline int supportSize(uchar4 support) { + return (support.x+support.y) * (support.z+support.w); +} + +__device__ inline short2 choosePoint(uchar4 sup1, uchar4 sup2, float dot1, float dot2, short2 screen1, short2 screen2) { + //return (float(supportSize(sup2))*dot1 > float(supportSize(sup1))*dot2) ? screen2 : screen1; + return (dot1 > dot2) ? screen2 : screen1; +} + +__device__ inline int unpackCameraID(short2 p) { + return p.x >> 12; +} + +/** + * Identify which source has the best support region for a given pixel. + */ +__global__ void best_sources_kernel( + TextureObject<float4> normals1, + TextureObject<float4> normals2, + TextureObject<uchar4> support1, + TextureObject<uchar4> support2, + TextureObject<float> depth1, + TextureObject<float> depth2, + TextureObject<short2> screen, + float4x4 transform, + //float3x3 transformR, + ftl::rgbd::Camera cam1, + ftl::rgbd::Camera cam2, + int id1, + int id2) { + + const int x = (blockIdx.x*blockDim.x + threadIdx.x); + const int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x >= 0 && y >= 0 && x < screen.width() && y < screen.height()) { + const float d1 = depth1.tex2D(x,y); + + const short3 scr2 = getScreenPos(x, y, d1, cam1, cam2, transform); + short2 bestPoint = packScreen(x,y,0); + + if (scr2.x >= 0 && scr2.y >= 0 && scr2.x < cam2.width && scr2.y < cam2.height) { + uchar4 sup1 = support1.tex2D(x,y); + uchar4 sup2 = support2.tex2D(scr2.x,scr2.y); + const float d2 = depth2.tex2D(scr2.x,scr2.y); + float3 n1 = transform.getFloat3x3() * make_float3(normals1.tex2D(x,y)); + float3 n2 = make_float3(normals2.tex2D(scr2.x,scr2.y)); + + float3 camray = cam2.screenToCam(scr2.x,scr2.y,1.0f); + camray /= length(camray); + const float dot1 = dot(camray, n1); + const float dot2 = dot(camray, n2); + + bestPoint = (fabs(scr2.z - d2) < 0.04f) ? choosePoint(sup1, sup2, dot1, dot2, packScreen(x,y,id1), packScreen(scr2,id2)) : packScreen(x,y,6); + //bestPoint = choosePoint(sup1, sup2, dot1, dot2, packScreen(x,y,id1), packScreen(scr2,id2)); + //bestPoint = (d1 < d2) ? packScreen(x,y,id1) : packScreen(x,y,id2); + + bestPoint = (fabs(scr2.z - d2) < 0.04f) ? packScreen(scr2,id2) : packScreen(scr2,id1); + } + + screen(x,y) = bestPoint; + + /*if (s.x >= 0 && s.y >= 0) { + auto norm1 = make_float3(n1.tex2D(x,y)); + const auto norm2 = make_float3(n2.tex2D(s.x,s.y)); + //n2(s.x,s.y) = norm1; + + float3 cent1 = make_float3(c1.tex2D(x,y)); + const auto cent2 = make_float3(c2.tex2D(s.x,s.y)); + + if (cent2.x+cent2.y+cent2.z > 0.0f && norm2.x+norm2.y+norm2.z > 0.0f) { + norm1 += poseInv1.getFloat3x3() * (pose2.getFloat3x3() * norm2); + n1(x,y) = make_float4(norm1, 0.0f); + cent1 += poseInv1 * (pose2 * cent2); // FIXME: Transform between camera spaces + cent1 /= 2.0f; + c1(x,y) = make_float4(cent1, 0.0f); + //c2(s.x,s.y) = cent1; + + //contribs1(x,y) = contribs1.tex2D(x,y) + 1.0f; + } + // contribs2(s.x,s.y) = contribs2.tex2D(s.x,s.y) + 1.0f; + }*/ + } +} + +void ftl::cuda::best_sources( + ftl::cuda::TextureObject<float4> &normals1, + ftl::cuda::TextureObject<float4> &normals2, + ftl::cuda::TextureObject<uchar4> &support1, + ftl::cuda::TextureObject<uchar4> &support2, + ftl::cuda::TextureObject<float> &depth1, + ftl::cuda::TextureObject<float> &depth2, + ftl::cuda::TextureObject<short2> &screen, + const float4x4 &transform, + const ftl::rgbd::Camera &cam1, + const ftl::rgbd::Camera &cam2, + int id1, + int id2, + cudaStream_t stream) { + + const dim3 gridSize((screen.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (screen.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + best_sources_kernel<<<gridSize, blockSize, 0, stream>>>(normals1, normals2, support1, support2, depth1, depth2, screen, transform, cam1, cam2, id1, id2); + cudaSafeCall( cudaGetLastError() ); +} + +/** + * Identify which source has the best support region for a given pixel. + */ + __global__ void aggregate_sources_kernel( + TextureObject<float4> n1, + TextureObject<float4> n2, + TextureObject<float4> c1, + TextureObject<float4> c2, + TextureObject<float> depth1, + //TextureObject<float> depth2, + //TextureObject<short2> screen, + float4x4 transform, + //float3x3 transformR, + ftl::rgbd::Camera cam1, + ftl::rgbd::Camera cam2) { + + const int x = (blockIdx.x*blockDim.x + threadIdx.x); + const int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x >= 0 && y >= 0 && x < n1.width() && y < n1.height()) { + const float d1 = depth1.tex2D(x,y); + + if (d1 > cam1.minDepth && d1 < cam1.maxDepth) { + //const short3 s = getScreenPos(x, y, d1, cam1, cam2, transform); + const float3 camPos = transform * cam1.screenToCam(x, y, d1); + const int2 s = cam2.camToScreen<int2>(camPos); + + if (s.x >= 0 && s.y >= 0 && s.x < n2.width() && s.y < n2.height()) { + auto norm1 = make_float3(n1.tex2D(x,y)); + const auto norm2 = make_float3(n2.tex2D(s.x,s.y)); + //n2(s.x,s.y) = norm1; + + float3 cent1 = make_float3(c1.tex2D(x,y)); + const auto cent2 = transform.getInverse() * make_float3(c2.tex2D(s.x,s.y)); + + //printf("MERGING %f\n", length(cent2-cent1)); + + if (cent2.x+cent2.y+cent2.z > 0.0f && norm2.x+norm2.y+norm2.z > 0.0f && length(cent2-cent1) < 0.04f) { + norm1 += norm2; + norm1 /= 2.0f; + n1(x,y) = make_float4(norm1, 0.0f); + cent1 += cent2; + cent1 /= 2.0f; + c1(x,y) = make_float4(cent1, 0.0f); + //c2(s.x,s.y) = cent1; + + //contribs1(x,y) = contribs1.tex2D(x,y) + 1.0f; + } + // contribs2(s.x,s.y) = contribs2.tex2D(s.x,s.y) + 1.0f; + } + } + } +} + +void ftl::cuda::aggregate_sources( + ftl::cuda::TextureObject<float4> &n1, + ftl::cuda::TextureObject<float4> &n2, + ftl::cuda::TextureObject<float4> &c1, + ftl::cuda::TextureObject<float4> &c2, + ftl::cuda::TextureObject<float> &depth1, + //ftl::cuda::TextureObject<float> &depth2, + //ftl::cuda::TextureObject<short2> &screen, + const float4x4 &transform, + const ftl::rgbd::Camera &cam1, + const ftl::rgbd::Camera &cam2, + cudaStream_t stream) { + + const dim3 gridSize((n1.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (n1.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + aggregate_sources_kernel<<<gridSize, blockSize, 0, stream>>>(n1, n2, c1, c2, depth1, transform, cam1, cam2); + cudaSafeCall( cudaGetLastError() ); +} + +__device__ static uchar4 HSVtoRGB(int H, float S, float V) { + const float C = S * V; + const float X = C * (1 - fabs(fmodf(H / 60.0f, 2) - 1)); + const float m = V - C; + float Rs, Gs, Bs; + + if(H >= 0 && H < 60) { + Rs = C; + Gs = X; + Bs = 0; + } + else if(H >= 60 && H < 120) { + Rs = X; + Gs = C; + Bs = 0; + } + else if(H >= 120 && H < 180) { + Rs = 0; + Gs = C; + Bs = X; + } + else if(H >= 180 && H < 240) { + Rs = 0; + Gs = X; + Bs = C; + } + else if(H >= 240 && H < 300) { + Rs = X; + Gs = 0; + Bs = C; + } + else { + Rs = C; + Gs = 0; + Bs = X; + } + + return make_uchar4((Bs + m) * 255, (Gs + m) * 255, (Rs + m) * 255, 0); +} + +/** + * Render each pixel is a colour corresponding to the source camera with the + * best support window. + */ + __global__ void vis_best_sources_kernel( + TextureObject<short2> screen, + TextureObject<uchar4> colour, + int myid, + int count) { + + const int x = (blockIdx.x*blockDim.x + threadIdx.x); + const int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x >= 0 && y >= 0 && x < colour.width() && y < colour.height()) { + short2 s = screen.tex2D(x,y); + int id = unpackCameraID(s); + + uchar4 c = HSVtoRGB((360 / count) * id, 0.6f, 0.85f); + if (myid != id) colour(x,y) = c; + //colour(x,y) = c; + } +} + +void ftl::cuda::vis_best_sources( + ftl::cuda::TextureObject<short2> &screen, + ftl::cuda::TextureObject<uchar4> &colour, + int myid, + int count, + cudaStream_t stream) { + + const dim3 gridSize((colour.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (colour.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + vis_best_sources_kernel<<<gridSize, blockSize, 0, stream>>>(screen, colour, myid, count); + cudaSafeCall( cudaGetLastError() ); +} + +/*void ftl::cuda::aggregate_sources( + ftl::cuda::TextureObject<float4> &n1, + ftl::cuda::TextureObject<float4> &n2, + ftl::cuda::TextureObject<float4> &c1, + ftl::cuda::TextureObject<float4> &c2, + ftl::cuda::TextureObject<float> &contribs1, + ftl::cuda::TextureObject<float> &contribs2, + ftl::cuda::TextureObject<short2> &screen, + const float4x4 &poseInv1, + const float4x4 &pose2, + cudaStream_t stream) { + + const dim3 gridSize((screen.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (screen.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + aggregate_sources_kernel<<<gridSize, blockSize, 0, stream>>>(n1, n2, c1, c2, contribs1, contribs2, screen, poseInv1, pose2); + cudaSafeCall( cudaGetLastError() ); +}*/ + +// ==== Normalise aggregations ================================================= + +__global__ void normalise_aggregations_kernel( + TextureObject<float4> norms, + TextureObject<float4> cents, + TextureObject<float> contribs) { + + const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; + const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x < norms.width() && y < norms.height()) { + const float contrib = contribs.tex2D((int)x,(int)y); + + const auto a = norms.tex2D((int)x,(int)y); + const auto b = cents.tex2D(x,y); + //const float4 normal = normals.tex2D((int)x,(int)y); + + //out(x,y) = (contrib == 0.0f) ? make<B>(a) : make<B>(a / contrib); + + if (contrib > 0.0f) { + norms(x,y) = a / (contrib+1.0f); + cents(x,y) = b / (contrib+1.0f); + } + } +} + +void ftl::cuda::normalise_aggregations(TextureObject<float4> &norms, TextureObject<float4> ¢s, TextureObject<float> &contribs, cudaStream_t stream) { + const dim3 gridSize((norms.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (norms.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); + const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); + + normalise_aggregations_kernel<<<gridSize, blockSize, 0, stream>>>(norms, cents, contribs); + cudaSafeCall( cudaGetLastError() ); +} + diff --git a/components/operators/src/mvmls.cpp b/components/operators/src/mvmls.cpp new file mode 100644 index 0000000000000000000000000000000000000000..4c02a7607f1d6a506c1f60cbd1f25eabd2cb5732 --- /dev/null +++ b/components/operators/src/mvmls.cpp @@ -0,0 +1,340 @@ +#include <ftl/operators/mvmls.hpp> +#include "smoothing_cuda.hpp" +#include <ftl/utility/matrix_conversion.hpp> +#include "mvmls_cuda.hpp" + +using ftl::operators::MultiViewMLS; +using ftl::codecs::Channel; +using cv::cuda::GpuMat; +using ftl::rgbd::Format; + +MultiViewMLS::MultiViewMLS(ftl::Configurable *cfg) : ftl::operators::Operator(cfg) { + +} + +MultiViewMLS::~MultiViewMLS() { + +} + +bool MultiViewMLS::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cudaStream_t stream) { + cv::cuda::Stream cvstream = cv::cuda::StreamAccessor::wrapStream(stream); + + float thresh = config()->value("mls_threshold", 0.4f); + float col_smooth = config()->value("mls_colour_smoothing", 30.0f); + int iters = config()->value("mls_iterations", 3); + int radius = config()->value("mls_radius",5); + //bool aggre = config()->value("aggregation", true); + int win = config()->value("cost_function",1); + bool do_corr = config()->value("merge_corresponding", true); + bool do_aggr = config()->value("merge_mls", false); + bool cull_zero = config()->value("cull_no_confidence", false); + //bool show_best_source = config()->value("show_pixel_source", false); + + ftl::cuda::MvMLSParams params; + params.range = config()->value("search_range", 0.05f); + params.fill_match = config()->value("fill_match", 50.0f); + params.fill_threshold = config()->value("fill_threshold", 0.0f); + params.match_threshold = config()->value("match_threshold", 0.3f); + params.colour_smooth = config()->value("colour_smooth", 150.0f); + params.spatial_smooth = config()->value("spatial_smooth", 0.04f); + params.cost_ratio = config()->value("cost_ratio", 0.2f); + params.cost_threshold = config()->value("cost_threshold", 1.0f); + + // Make sure we have enough buffers + if (normals_horiz_.size() < in.frames.size()) { + normals_horiz_.resize(in.frames.size()); + centroid_horiz_.resize(in.frames.size()); + centroid_vert_.resize(in.frames.size()); + contributions_.resize(in.frames.size()); + } + + // Make sure all buffers are at correct resolution and are allocated + for (size_t i=0; i<in.frames.size(); ++i) { + auto &f = in.frames[i]; + auto size = f.get<GpuMat>(Channel::Depth).size(); + centroid_horiz_[i].create(size.height, size.width); + normals_horiz_[i].create(size.height, size.width); + centroid_vert_[i].create(size.width, size.height); + contributions_[i].create(size.width, size.height); + + if (!f.hasChannel(Channel::Normals)) { + LOG(ERROR) << "Required normals channel missing for MLS"; + return false; + } + if (!f.hasChannel(Channel::Support1)) { + LOG(ERROR) << "Required cross support channel missing for MLS"; + return false; + } + + // Create required channels + f.create<GpuMat>(Channel::Confidence, Format<float>(size)); + f.createTexture<float>(Channel::Confidence); + f.create<GpuMat>(Channel::Screen, Format<short2>(size)); + f.createTexture<short2>(Channel::Screen); + } + + for (int iter=0; iter<iters; ++iter) { + // Step 1: + // Calculate correspondences and adjust depth values + // Step 2: + // Find corresponding points and perform aggregation of any correspondences + // For each camera combination + if (do_corr) { + for (size_t i=0; i<in.frames.size(); ++i) { + auto &f1 = in.frames[i]; + //f1.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0.0f), cvstream); + f1.get<GpuMat>(Channel::Confidence).setTo(cv::Scalar(0.0f), cvstream); + + Eigen::Vector4d d1(0.0, 0.0, 1.0, 0.0); + d1 = in.sources[i]->getPose() * d1; + + for (size_t j=0; j<in.frames.size(); ++j) { + if (i == j) continue; + + //LOG(INFO) << "Running phase1"; + + auto &f2 = in.frames[j]; + auto s1 = in.sources[i]; + auto s2 = in.sources[j]; + + // Are cameras facing similar enough direction? + Eigen::Vector4d d2(0.0, 0.0, 1.0, 0.0); + d2 = in.sources[j]->getPose() * d2; + // No, so skip this combination + if (d1.dot(d2) <= 0.0) continue; + + auto pose1 = MatrixConversion::toCUDA(s1->getPose().cast<float>()); + auto pose1_inv = MatrixConversion::toCUDA(s1->getPose().cast<float>().inverse()); + auto pose2 = MatrixConversion::toCUDA(s2->getPose().cast<float>().inverse()); + auto pose2_inv = MatrixConversion::toCUDA(s2->getPose().cast<float>()); + + auto transform = pose2 * pose1; + + //Calculate screen positions of estimated corresponding points + ftl::cuda::correspondence( + f1.getTexture<float>(Channel::Depth), + f2.getTexture<float>(Channel::Depth), + f1.getTexture<uchar4>(Channel::Colour), + f2.getTexture<uchar4>(Channel::Colour), + // TODO: Add normals and other things... + f1.getTexture<short2>(Channel::Screen), + f1.getTexture<float>(Channel::Confidence), + f1.getTexture<int>(Channel::Mask), + pose1, + pose1_inv, + pose2, + s1->parameters(), + s2->parameters(), + params, + win, + stream + ); + + // Also calculate best source for each point + /*ftl::cuda::best_sources( + f1.getTexture<uchar4>(Channel::Support1), + f2.getTexture<uchar4>(Channel::Support1), + f1.getTexture<float>(Channel::Depth), + f2.getTexture<float>(Channel::Depth), + f1.getTexture<short2>(Channel::Screen), + transform, + s1->parameters(), + s2->parameters(), + i, j, stream + );*/ + } + } + } + + // Find best source for every pixel + /*for (size_t i=0; i<in.frames.size(); ++i) { + auto &f1 = in.frames[i]; + //f1.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0.0f), cvstream); + //f1.get<GpuMat>(Channel::Confidence).setTo(cv::Scalar(0.0f), cvstream); + + Eigen::Vector4d d1(0.0, 0.0, 1.0, 0.0); + d1 = in.sources[i]->getPose() * d1; + + for (size_t j=0; j<in.frames.size(); ++j) { + if (i == j) continue; + + //LOG(INFO) << "Running phase1"; + + auto &f2 = in.frames[j]; + auto s1 = in.sources[i]; + auto s2 = in.sources[j]; + + // Are cameras facing similar enough direction? + Eigen::Vector4d d2(0.0, 0.0, 1.0, 0.0); + d2 = in.sources[j]->getPose() * d2; + // No, so skip this combination + if (d1.dot(d2) <= 0.0) continue; + + auto pose1 = MatrixConversion::toCUDA(s1->getPose().cast<float>()); + auto pose1_inv = MatrixConversion::toCUDA(s1->getPose().cast<float>().inverse()); + auto pose2 = MatrixConversion::toCUDA(s2->getPose().cast<float>().inverse()); + auto pose2_inv = MatrixConversion::toCUDA(s2->getPose().cast<float>()); + + auto transform = pose2 * pose1; + + // Also calculate best source for each point + ftl::cuda::best_sources( + f1.getTexture<float4>(Channel::Normals), + f2.getTexture<float4>(Channel::Normals), + f1.getTexture<uchar4>(Channel::Support1), + f2.getTexture<uchar4>(Channel::Support1), + f1.getTexture<float>(Channel::Depth), + f2.getTexture<float>(Channel::Depth), + f1.getTexture<short2>(Channel::Screen), + transform, + s1->parameters(), + s2->parameters(), + i, j, stream + ); + } + }*/ + + // Step 2: + // Do the horizontal and vertical MLS aggregations for each source + // But don't do the final move step. + for (size_t i=0; i<in.frames.size(); ++i) { + auto &f = in.frames[i]; + auto *s = in.sources[i]; + + // Clear data + cv::cuda::GpuMat data(contributions_[i].height(), contributions_[i].width(), CV_32F, contributions_[i].pixelPitch()); + data.setTo(cv::Scalar(0.0f), cvstream); + + if (cull_zero && iter == iters-1) { + ftl::cuda::zero_confidence( + f.getTexture<float>(Channel::Confidence), + f.getTexture<float>(Channel::Depth), + stream + ); + } + + ftl::cuda::mls_aggr_horiz( + f.createTexture<uchar4>(Channel::Support1), + f.createTexture<float4>(Channel::Normals), + normals_horiz_[i], + f.createTexture<float>(Channel::Depth), + centroid_horiz_[i], + f.createTexture<uchar4>(Channel::Colour), + thresh, + col_smooth, + radius, + s->parameters(), + stream + ); + + ftl::cuda::mls_aggr_vert( + f.getTexture<uchar4>(Channel::Support1), + normals_horiz_[i], + f.getTexture<float4>(Channel::Normals), + centroid_horiz_[i], + centroid_vert_[i], + f.getTexture<uchar4>(Channel::Colour), + f.getTexture<float>(Channel::Depth), + thresh, + col_smooth, + radius, + s->parameters(), + stream + ); + } + + // Step 3: + // Find corresponding points and perform aggregation of any correspondences + // For each camera combination + if (do_aggr) { + for (size_t i=0; i<in.frames.size(); ++i) { + auto &f1 = in.frames[i]; + //f1.get<GpuMat>(Channel::Depth2).setTo(cv::Scalar(0.0f), cvstream); + f1.get<GpuMat>(Channel::Confidence).setTo(cv::Scalar(0.0f), cvstream); + + Eigen::Vector4d d1(0.0, 0.0, 1.0, 0.0); + d1 = in.sources[i]->getPose() * d1; + + for (size_t j=0; j<in.frames.size(); ++j) { + if (i == j) continue; + + //LOG(INFO) << "Running phase1"; + + auto &f2 = in.frames[j]; + auto s1 = in.sources[i]; + auto s2 = in.sources[j]; + + // Are cameras facing similar enough direction? + Eigen::Vector4d d2(0.0, 0.0, 1.0, 0.0); + d2 = in.sources[j]->getPose() * d2; + // No, so skip this combination + if (d1.dot(d2) <= 0.0) continue; + + auto pose1 = MatrixConversion::toCUDA(s1->getPose().cast<float>()); + auto pose1_inv = MatrixConversion::toCUDA(s1->getPose().cast<float>().inverse()); + auto pose2 = MatrixConversion::toCUDA(s2->getPose().cast<float>().inverse()); + auto pose2_inv = MatrixConversion::toCUDA(s2->getPose().cast<float>()); + + auto transform = pose2 * pose1; + + // For the corresponding points, combine normals and centroids + ftl::cuda::aggregate_sources( + f1.getTexture<float4>(Channel::Normals), + f2.getTexture<float4>(Channel::Normals), + centroid_vert_[i], + centroid_vert_[j], + f1.getTexture<float>(Channel::Depth), + //contributions_[i], + //contributions_[j], + //f1.getTexture<short2>(Channel::Screen), + transform, + s1->parameters(), + s2->parameters(), + stream + ); + + //LOG(INFO) << "Correspondences done... " << i; + } + } + } + + // Step 3: + // Normalise aggregations and move the points + for (size_t i=0; i<in.frames.size(); ++i) { + auto &f = in.frames[i]; + auto *s = in.sources[i]; + auto size = f.get<GpuMat>(Channel::Depth).size(); + + /*if (do_corr) { + ftl::cuda::normalise_aggregations( + f.getTexture<float4>(Channel::Normals), + centroid_vert_[i], + contributions_[i], + stream + ); + }*/ + + ftl::cuda::mls_adjust_depth( + f.getTexture<float4>(Channel::Normals), + centroid_vert_[i], + f.getTexture<float>(Channel::Depth), + f.createTexture<float>(Channel::Depth2, ftl::rgbd::Format<float>(size)), + s->parameters(), + stream + ); + + f.swapChannels(Channel::Depth, Channel::Depth2); + + /*if (show_best_source) { + ftl::cuda::vis_best_sources( + f.getTexture<short2>(Channel::Screen), + f.getTexture<uchar4>(Channel::Colour), + i, + 7, stream + ); + }*/ + } + } + + return true; +} diff --git a/components/operators/src/mvmls_cuda.hpp b/components/operators/src/mvmls_cuda.hpp new file mode 100644 index 0000000000000000000000000000000000000000..93b1e8d882848490aec96a291d58805c2d2dbf03 --- /dev/null +++ b/components/operators/src/mvmls_cuda.hpp @@ -0,0 +1,101 @@ +#ifndef _FTL_CUDA_MVMLS_HPP_ +#define _FTL_CUDA_MVMLS_HPP_ + +#include <ftl/rgbd/camera.hpp> +#include <ftl/cuda_common.hpp> +#include <ftl/cuda_matrix_util.hpp> + +namespace ftl { +namespace cuda { + +struct MvMLSParams { + float spatial_smooth; + float colour_smooth; + float fill_match; + float fill_threshold; + float match_threshold; + float cost_ratio; + float cost_threshold; + float range; + uint flags; +}; + +void correspondence( + ftl::cuda::TextureObject<float> &d1, + ftl::cuda::TextureObject<float> &d2, + ftl::cuda::TextureObject<uchar4> &c1, + ftl::cuda::TextureObject<uchar4> &c2, + ftl::cuda::TextureObject<short2> &screen, + ftl::cuda::TextureObject<float> &conf, + ftl::cuda::TextureObject<int> &mask, + float4x4 &pose1, + float4x4 &pose1_inv, + float4x4 &pose2, + const ftl::rgbd::Camera &cam1, + const ftl::rgbd::Camera &cam2, const ftl::cuda::MvMLSParams ¶ms, int func, + cudaStream_t stream); + +void zero_confidence( + ftl::cuda::TextureObject<float> &conf, + ftl::cuda::TextureObject<float> &depth, + cudaStream_t stream); + +/*void aggregate_sources( + ftl::cuda::TextureObject<float4> &n1, + ftl::cuda::TextureObject<float4> &n2, + ftl::cuda::TextureObject<float4> &c1, + ftl::cuda::TextureObject<float4> &c2, + ftl::cuda::TextureObject<float> &contribs1, + ftl::cuda::TextureObject<float> &contribs2, + ftl::cuda::TextureObject<short2> &screen, + //const float4x4 &pose1, + //const float4x4 &poseInv2, + const float4x4 &poseInv1, + const float4x4 &pose2, + cudaStream_t stream);*/ + +void aggregate_sources( + ftl::cuda::TextureObject<float4> &n1, + ftl::cuda::TextureObject<float4> &n2, + ftl::cuda::TextureObject<float4> &c1, + ftl::cuda::TextureObject<float4> &c2, + ftl::cuda::TextureObject<float> &depth1, + //ftl::cuda::TextureObject<float> &depth2, + //ftl::cuda::TextureObject<short2> &screen, + const float4x4 &transform, + const ftl::rgbd::Camera &cam1, + const ftl::rgbd::Camera &cam2, + cudaStream_t stream); + +void best_sources( + ftl::cuda::TextureObject<float4> &normals1, + ftl::cuda::TextureObject<float4> &normals2, + ftl::cuda::TextureObject<uchar4> &support1, + ftl::cuda::TextureObject<uchar4> &suppor2, + ftl::cuda::TextureObject<float> &depth1, + ftl::cuda::TextureObject<float> &depth2, + ftl::cuda::TextureObject<short2> &screen, + const float4x4 &transform, + const ftl::rgbd::Camera &cam1, + const ftl::rgbd::Camera &cam2, + int id1, + int id2, + cudaStream_t stream); + +void vis_best_sources( + ftl::cuda::TextureObject<short2> &screen, + ftl::cuda::TextureObject<uchar4> &colour, + int myid, + int count, + cudaStream_t stream); + +void normalise_aggregations( + ftl::cuda::TextureObject<float4> &norms, + ftl::cuda::TextureObject<float4> ¢s, + ftl::cuda::TextureObject<float> &contribs, + cudaStream_t stream); + +} +} + +#endif diff --git a/components/operators/src/operator.cpp b/components/operators/src/operator.cpp index e55c181c4604a53c2b1090bdee8233242bb6f177..dd821ee6fdd2b967e5ac46f3a4f77c57d59aed6b 100644 --- a/components/operators/src/operator.cpp +++ b/components/operators/src/operator.cpp @@ -46,16 +46,32 @@ bool Graph::apply(FrameSet &in, FrameSet &out, cudaStream_t stream) { if (in.frames.size() != out.frames.size()) return false; for (auto &i : operators_) { - // Make sure there are enough instances - while (i.instances.size() < in.frames.size()) { + if (i.instances.size() < 1) { i.instances.push_back(i.maker->make()); } - for (int j=0; j<in.frames.size(); ++j) { - auto *instance = i.instances[j]; + if (i.instances[0]->type() == Operator::Type::OneToOne) { + // 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()) { - 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(); + } } } } diff --git a/components/operators/src/segmentation.cpp b/components/operators/src/segmentation.cpp index 08b4de467b74db4bbcb2f921a9fcbb61d3f1ca2c..fb015b6b16e1aa7e1dcac9735103c8c6af41567e 100644 --- a/components/operators/src/segmentation.cpp +++ b/components/operators/src/segmentation.cpp @@ -22,7 +22,8 @@ bool CrossSupport::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd: out.createTexture<uchar4>(Channel::Support2, ftl::rgbd::Format<uchar4>(in.get<cv::cuda::GpuMat>(Channel::Colour).size())), config()->value("depth_tau", 0.04f), config()->value("v_max", 5), - config()->value("h_max", 5), stream + config()->value("h_max", 5), + config()->value("symmetric", true), stream ); } //else { ftl::cuda::support_region( @@ -30,7 +31,8 @@ bool CrossSupport::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd: out.createTexture<uchar4>(Channel::Support1, ftl::rgbd::Format<uchar4>(in.get<cv::cuda::GpuMat>(Channel::Colour).size())), config()->value("tau", 5.0f), config()->value("v_max", 5), - config()->value("h_max", 5), stream + config()->value("h_max", 5), + config()->value("symmetric", true), stream ); //} diff --git a/components/operators/src/segmentation.cu b/components/operators/src/segmentation.cu index 3bfcbc0f5769f10a9e006636cea5409ccea89dac..c16e647931f7d4c4d92551f44f6242fc415bd91d 100644 --- a/components/operators/src/segmentation.cu +++ b/components/operators/src/segmentation.cu @@ -22,7 +22,7 @@ __device__ inline float cross<float>(float p1, float p2) { return fabs(p1-p2); } -template <typename T> +template <typename T, bool SYM> __device__ uchar4 calculate_support_region(const TextureObject<T> &img, int x, int y, float tau, int v_max, int h_max) { int x_min = max(0, x - h_max); int x_max = min(img.width()-1, x + h_max); @@ -79,17 +79,24 @@ __device__ uchar4 calculate_support_region(const TextureObject<T> &img, int x, i } if (v > y_max) result.w = y_max - y; + // Make symetric left/right and up/down + if (SYM) { + result.x = min(result.x, result.y); + result.y = result.x; + result.z = min(result.z, result.w); + result.w = result.z; + } return result; } -template <typename T> +template <typename T, bool SYM> __global__ void support_region_kernel(TextureObject<T> img, TextureObject<uchar4> region, float tau, int v_max, int h_max) { const int x = blockIdx.x*blockDim.x + threadIdx.x; const int y = blockIdx.y*blockDim.y + threadIdx.y; if (x < 0 || y < 0 || x >= img.width() || y >= img.height()) return; - region(x,y) = calculate_support_region(img, x, y, tau, v_max, h_max); + region(x,y) = calculate_support_region<T,SYM>(img, x, y, tau, v_max, h_max); } void ftl::cuda::support_region( @@ -97,13 +104,15 @@ void ftl::cuda::support_region( ftl::cuda::TextureObject<uchar4> ®ion, float tau, int v_max, - int h_max, + int h_max, + bool sym, cudaStream_t stream) { const dim3 gridSize((region.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (region.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - support_region_kernel<<<gridSize, blockSize, 0, stream>>>(colour, region, tau, v_max, h_max); + if (sym) support_region_kernel<uchar4, true><<<gridSize, blockSize, 0, stream>>>(colour, region, tau, v_max, h_max); + else support_region_kernel<uchar4, false><<<gridSize, blockSize, 0, stream>>>(colour, region, tau, v_max, h_max); cudaSafeCall( cudaGetLastError() ); @@ -118,12 +127,13 @@ void ftl::cuda::support_region( float tau, int v_max, int h_max, + bool sym, cudaStream_t stream) { const dim3 gridSize((region.width() + T_PER_BLOCK - 1)/T_PER_BLOCK, (region.height() + T_PER_BLOCK - 1)/T_PER_BLOCK); const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); - support_region_kernel<<<gridSize, blockSize, 0, stream>>>(depth, region, tau, v_max, h_max); + support_region_kernel<float, true><<<gridSize, blockSize, 0, stream>>>(depth, region, tau, v_max, h_max); cudaSafeCall( cudaGetLastError() ); diff --git a/components/operators/src/segmentation_cuda.hpp b/components/operators/src/segmentation_cuda.hpp index 5ef55abb10a0d61aa83f900761b26352a3ae4a87..c2cb390d9c0ee62a33127eec1720cf0d6fee8cae 100644 --- a/components/operators/src/segmentation_cuda.hpp +++ b/components/operators/src/segmentation_cuda.hpp @@ -9,13 +9,13 @@ namespace cuda { void support_region( ftl::cuda::TextureObject<uchar4> &colour, ftl::cuda::TextureObject<uchar4> ®ion, - float tau, int v_max, int h_max, + float tau, int v_max, int h_max, bool sym, cudaStream_t stream); void support_region( ftl::cuda::TextureObject<float> &depth, ftl::cuda::TextureObject<uchar4> ®ion, - float tau, int v_max, int h_max, + float tau, int v_max, int h_max, bool sym, cudaStream_t stream); void vis_support_region( diff --git a/components/operators/src/smoothing.cpp b/components/operators/src/smoothing.cpp index a4b23ab7c46fae80a13c5c4a4dd761dd81b6d822..2eafe7977a827cd0a1e90017f749fd1245ce1b68 100644 --- a/components/operators/src/smoothing.cpp +++ b/components/operators/src/smoothing.cpp @@ -253,6 +253,11 @@ bool AggreMLS::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, ftl::rgbd::Sou return false; } + if (!in.hasChannel(Channel::Support1)) { + LOG(ERROR) << "Required support channel missing for MLS"; + return false; + } + auto size = in.get<GpuMat>(Channel::Depth).size(); centroid_horiz_.create(size.height, size.width); normals_horiz_.create(size.height, size.width); diff --git a/components/renderers/cpp/src/reprojection.cu b/components/renderers/cpp/src/reprojection.cu index 8a075b65382f7b574c6c4496557364a7a3aef1ee..e6490c47eaf9033c2077cdd06457b3ff4f59103e 100644 --- a/components/renderers/cpp/src/reprojection.cu +++ b/components/renderers/cpp/src/reprojection.cu @@ -66,7 +66,7 @@ __global__ void reprojection_kernel( TextureObject<B> out, // Accumulated output TextureObject<float> contrib, SplatParams params, - Camera camera, float4x4 poseInv) { + Camera camera, float4x4 transform, float3x3 transformR) { const int x = (blockIdx.x*blockDim.x + threadIdx.x); const int y = blockIdx.y*blockDim.y + threadIdx.y; @@ -74,10 +74,10 @@ __global__ void reprojection_kernel( const float d = depth_in.tex2D((int)x, (int)y); if (d < params.camera.minDepth || d > params.camera.maxDepth) return; - const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d); + //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; + const float3 camPos = transform * params.camera.screenToCam(x, y, d); if (camPos.z < camera.minDepth) return; if (camPos.z > camera.maxDepth) return; const float2 screenPos = camera.camToScreen<float2>(camPos); @@ -86,7 +86,7 @@ __global__ void reprojection_kernel( 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)); + const float3 n = transformR * 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); @@ -123,7 +123,7 @@ void ftl::cuda::reproject( TextureObject<B> &out, // Accumulated output TextureObject<float> &contrib, const SplatParams ¶ms, - const Camera &camera, const float4x4 &poseInv, cudaStream_t stream) { + const Camera &camera, const float4x4 &transform, const float3x3 &transformR, 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); @@ -136,7 +136,8 @@ void ftl::cuda::reproject( contrib, params, camera, - poseInv + transform, + transformR ); cudaSafeCall( cudaGetLastError() ); } @@ -150,7 +151,7 @@ template void ftl::cuda::reproject( ftl::cuda::TextureObject<float> &contrib, const ftl::render::SplatParams ¶ms, const ftl::rgbd::Camera &camera, - const float4x4 &poseInv, cudaStream_t stream); + const float4x4 &transform, const float3x3 &transformR, cudaStream_t stream); template void ftl::cuda::reproject( ftl::cuda::TextureObject<float> &in, // Original colour image @@ -161,7 +162,7 @@ template void ftl::cuda::reproject( ftl::cuda::TextureObject<float> &contrib, const ftl::render::SplatParams ¶ms, const ftl::rgbd::Camera &camera, - const float4x4 &poseInv, cudaStream_t stream); + const float4x4 &transform, const float3x3 &transformR, cudaStream_t stream); template void ftl::cuda::reproject( ftl::cuda::TextureObject<float4> &in, // Original colour image @@ -172,7 +173,7 @@ template void ftl::cuda::reproject( ftl::cuda::TextureObject<float> &contrib, const ftl::render::SplatParams ¶ms, const ftl::rgbd::Camera &camera, - const float4x4 &poseInv, cudaStream_t stream); + const float4x4 &transform, const float3x3 &transformR, cudaStream_t stream); //============================================================================== // Without normals @@ -197,19 +198,19 @@ __global__ void reprojection_kernel( const float d = depth_in.tex2D((int)x, (int)y); if (d < params.camera.minDepth || d > params.camera.maxDepth) return; - const float3 worldPos = params.m_viewMatrixInverse * params.camera.screenToCam(x, y, d); + //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; + const float3 camPos = poseInv * params.camera.screenToCam(x, y, d); if (camPos.z < camera.minDepth) return; if (camPos.z > camera.maxDepth) return; - const uint2 screenPos = camera.camToScreen<uint2>(camPos); + const float2 screenPos = camera.camToScreen<float2>(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); + const float d2 = depth_src.tex2D((int)(screenPos.x+0.5f), (int)(screenPos.y+0.5f)); + const auto input = in.tex2D(screenPos.x, 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; diff --git a/components/renderers/cpp/src/splatter.cu b/components/renderers/cpp/src/splatter.cu index 6346daa883019453bef1d2f80be36ba5afa0aaf2..2986234bb3bbc24f762ff5ba0103ba173f4a0093 100644 --- a/components/renderers/cpp/src/splatter.cu +++ b/components/renderers/cpp/src/splatter.cu @@ -103,6 +103,40 @@ using ftl::cuda::warpSum; } } +/* + * Pass 1: Directly render each camera into virtual view but with no upsampling + * for sparse points. + */ + __global__ void dibr_merge_kernel(TextureObject<float> depth, + TextureObject<int> depth_out, + float4x4 transform, + ftl::rgbd::Camera cam, + SplatParams params) { + const int x = blockIdx.x*blockDim.x + threadIdx.x; + const int y = blockIdx.y*blockDim.y + threadIdx.y; + + const float d0 = depth.tex2D(x, y); + if (d0 <= cam.minDepth || d0 >= cam.maxDepth) return; + + const float3 camPos = transform * cam.screenToCam(x,y,d0); + //if (worldPos.x == MINF || (!(params.m_flags & ftl::render::kShowDisconMask) && worldPos.w < 0.0f)) return; + + // Find the virtual screen position of current point + //const float3 camPos = params.m_viewMatrix * make_float3(worldPos); + //if (camPos.z < params.camera.minDepth) return; + //if (camPos.z > params.camera.maxDepth) return; + + const float d = camPos.z; + + const uint2 screenPos = params.camera.camToScreen<uint2>(camPos); + const unsigned int cx = screenPos.x; + 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_out(cx,cy), d * 100000.0f); + } +} + 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); const dim3 blockSize(T_PER_BLOCK, T_PER_BLOCK); @@ -120,6 +154,14 @@ void ftl::cuda::dibr_merge(TextureObject<float4> &points, TextureObject<int> &de cudaSafeCall( cudaGetLastError() ); } +void ftl::cuda::dibr_merge(TextureObject<float> &depth, TextureObject<int> &depth_out, const float4x4 &transform, const ftl::rgbd::Camera &cam, SplatParams params, 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); + + dibr_merge_kernel<<<gridSize, blockSize, 0, stream>>>(depth, depth_out, transform, cam, params); + cudaSafeCall( cudaGetLastError() ); +} + //============================================================================== @@ -441,9 +483,11 @@ __global__ void dibr_normalise_kernel( const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; if (x < in.width() && y < in.height()) { + const float contrib = contribs.tex2D((int)x,(int)y); const A a = in.tex2D((int)x,(int)y); //const float4 normal = normals.tex2D((int)x,(int)y); - const float contrib = contribs.tex2D((int)x,(int)y); + + //out(x,y) = (contrib == 0.0f) ? make<B>(a) : make<B>(a / contrib); if (contrib > 0.0f) { out(x,y) = make<B>(a / contrib); @@ -464,3 +508,39 @@ void ftl::cuda::dibr_normalise(TextureObject<A> &in, TextureObject<B> &out, Text template void ftl::cuda::dibr_normalise<float4,uchar4>(TextureObject<float4> &in, TextureObject<uchar4> &out, TextureObject<float> &contribs, cudaStream_t stream); template void ftl::cuda::dibr_normalise<float,float>(TextureObject<float> &in, TextureObject<float> &out, TextureObject<float> &contribs, cudaStream_t stream); template void ftl::cuda::dibr_normalise<float4,float4>(TextureObject<float4> &in, TextureObject<float4> &out, TextureObject<float> &contribs, cudaStream_t stream); + + +// ===== Show bad colour normalise ============================================= + +__global__ void show_missing_colour_kernel( + TextureObject<float> depth, + TextureObject<uchar4> out, + TextureObject<float> contribs, + uchar4 bad_colour, + ftl::rgbd::Camera cam) { + const unsigned int x = blockIdx.x*blockDim.x + threadIdx.x; + const unsigned int y = blockIdx.y*blockDim.y + threadIdx.y; + + if (x < out.width() && y < out.height()) { + const float contrib = contribs.tex2D((int)x,(int)y); + const float d = depth.tex2D(x,y); + + if (contrib < 0.0000001f && d > cam.minDepth && d < cam.maxDepth) { + out(x,y) = bad_colour; + } + } +} + +void ftl::cuda::show_missing_colour( + TextureObject<float> &depth, + TextureObject<uchar4> &out, + TextureObject<float> &contribs, + uchar4 bad_colour, + const ftl::rgbd::Camera &cam, + 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); + + show_missing_colour_kernel<<<gridSize, blockSize, 0, stream>>>(depth, out, contribs, bad_colour, cam); + cudaSafeCall( cudaGetLastError() ); +} diff --git a/components/renderers/cpp/src/splatter_cuda.hpp b/components/renderers/cpp/src/splatter_cuda.hpp index 010a637188523030ea2a40ac3c6cdd720c3a0148..c81977cf38a4380df4143d2cd8d0609c69de8897 100644 --- a/components/renderers/cpp/src/splatter_cuda.hpp +++ b/components/renderers/cpp/src/splatter_cuda.hpp @@ -43,6 +43,14 @@ namespace cuda { ftl::render::SplatParams params, cudaStream_t stream); + void dibr_merge( + ftl::cuda::TextureObject<float> &depth, + ftl::cuda::TextureObject<int> &depth_out, + const float4x4 &transform, + const ftl::rgbd::Camera &cam, + ftl::render::SplatParams params, + cudaStream_t stream); + template <typename T> void splat( ftl::cuda::TextureObject<float4> &normals, @@ -72,7 +80,7 @@ namespace cuda { ftl::cuda::TextureObject<float> &contrib, const ftl::render::SplatParams ¶ms, const ftl::rgbd::Camera &camera, - const float4x4 &poseInv, cudaStream_t stream); + const float4x4 &transform, const float3x3 &transformR, cudaStream_t stream); template <typename A, typename B> void reproject( @@ -97,6 +105,14 @@ namespace cuda { ftl::cuda::TextureObject<float> &contribs, cudaStream_t stream); + void show_missing_colour( + ftl::cuda::TextureObject<float> &depth, + ftl::cuda::TextureObject<uchar4> &out, + ftl::cuda::TextureObject<float> &contribs, + uchar4 bad_colour, + const ftl::rgbd::Camera &cam, + cudaStream_t stream); + void show_mask( ftl::cuda::TextureObject<uchar4> &colour, ftl::cuda::TextureObject<int> &mask, diff --git a/components/renderers/cpp/src/tri_render.cpp b/components/renderers/cpp/src/tri_render.cpp index b3fba82a7de676f2aa963e80467a45dbf3f0bd13..5912b6480b109db2c3cce960ae5bca6abe6531f8 100644 --- a/components/renderers/cpp/src/tri_render.cpp +++ b/components/renderers/cpp/src/tri_render.cpp @@ -228,7 +228,8 @@ void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann cv::cuda::cvtColor(tmp,col, cv::COLOR_BGR2BGRA); } - auto poseInv = MatrixConversion::toCUDA(s->getPose().cast<float>().inverse()); + auto transform = MatrixConversion::toCUDA(s->getPose().cast<float>().inverse()) * params_.m_viewMatrixInverse; + auto transformR = MatrixConversion::toCUDA(s->getPose().cast<float>().inverse()).getFloat3x3(); if (mesh_) { ftl::cuda::reproject( @@ -240,7 +241,7 @@ void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann temp_.getTexture<float>(Channel::Contribution), params_, s->parameters(), - poseInv, stream + transform, transformR, stream ); } else { // Can't use normals with point cloud version @@ -252,7 +253,7 @@ void Triangular::__reprojectChannel(ftl::rgbd::Frame &output, ftl::codecs::Chann temp_.getTexture<float>(Channel::Contribution), params_, s->parameters(), - poseInv, stream + transform, stream ); } } @@ -300,9 +301,13 @@ void Triangular::_dibr(ftl::rgbd::Frame &out, cudaStream_t stream) { continue; } + auto transform = params_.m_viewMatrix * MatrixConversion::toCUDA(s->getPose().cast<float>()); + ftl::cuda::dibr_merge( - f.createTexture<float4>(Channel::Points), + f.createTexture<float>(Channel::Depth), temp_.createTexture<int>(Channel::Depth2), + transform, + s->parameters(), params_, stream ); } @@ -576,19 +581,19 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) { 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 + Channel::Smoothing, out); + scene_->frames[aligned_source].copyTo(Channel::Depth + Channel::Colour + Channel::Smoothing + Channel::Confidence, out); - if (chan == Channel::Normals) { + if (chan == Channel::ColourNormals) { // Convert normal to single float value - temp_.create<GpuMat>(Channel::Colour, Format<uchar4>(out.get<GpuMat>(Channel::Colour).size())).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), + out.create<GpuMat>(Channel::ColourNormals, Format<uchar4>(out.get<GpuMat>(Channel::Colour).size())).setTo(cv::Scalar(0,0,0,0), cvstream); + ftl::cuda::normal_visualise(scene_->frames[aligned_source].getTexture<float4>(Channel::Normals), out.createTexture<uchar4>(Channel::ColourNormals), 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); + //cv::cuda::swap(temp_.get<GpuMat>(Channel::Colour), out.create<GpuMat>(Channel::Normals)); + //out.resetTexture(Channel::Normals); } return true; @@ -603,6 +608,17 @@ bool Triangular::render(ftl::rgbd::VirtualSource *src, ftl::rgbd::Frame &out) { // Reprojection of colours onto surface _renderChannel(out, Channel::Colour, Channel::Colour, stream_); + + if (value("show_bad_colour", false)) { + ftl::cuda::show_missing_colour( + out.getTexture<float>(Channel::Depth), + out.getTexture<uchar4>(Channel::Colour), + temp_.getTexture<float>(Channel::Contribution), + make_uchar4(255,0,0,0), + camera, + stream_ + ); + } if (chan == Channel::Depth) { diff --git a/components/rgbd-sources/include/ftl/rgbd/frame.hpp b/components/rgbd-sources/include/ftl/rgbd/frame.hpp index d7b8292ffa066035bf12ec38095d1d312baccd86..e7a949600e6ba097aeda54460e83a1529851371e 100644 --- a/components/rgbd-sources/include/ftl/rgbd/frame.hpp +++ b/components/rgbd-sources/include/ftl/rgbd/frame.hpp @@ -233,7 +233,7 @@ ftl::cuda::TextureObject<T> &Frame::createTexture(ftl::codecs::Channel c, const template <typename T> ftl::cuda::TextureObject<T> &Frame::createTexture(ftl::codecs::Channel c, bool interpolated) { - if (!channels_.has(c)) throw ftl::exception("createTexture needs a format if the channel does not exist"); + if (!channels_.has(c)) throw ftl::exception(ftl::Formatter() << "createTexture needs a format if the channel does not exist: " << (int)c); auto &m = _get(c); diff --git a/components/rgbd-sources/include/ftl/rgbd/source.hpp b/components/rgbd-sources/include/ftl/rgbd/source.hpp index 7484788796dba398c525a208ad44708deadf3b70..8958173597a89c00748712a3e1fae69fbc630af0 100644 --- a/components/rgbd-sources/include/ftl/rgbd/source.hpp +++ b/components/rgbd-sources/include/ftl/rgbd/source.hpp @@ -31,6 +31,8 @@ class SnapshotReader; class VirtualSource; class Player; +typedef std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> RawCallback; + /** * RGBD Generic data source configurable entity. This class hides the * internal implementation of an RGBD source by providing accessor functions @@ -189,12 +191,12 @@ class Source : public ftl::Configurable { * Currently this only works for a net source since other sources don't * produce raw encoded data. */ - void addRawCallback(const std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> &); + void addRawCallback(const RawCallback &); /** * THIS DOES NOT WORK CURRENTLY. */ - void removeRawCallback(const std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> &); + void removeRawCallback(const RawCallback &); /** * INTERNAL. Used to send raw data to callbacks. diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp index 003984d8a5fdc9c4e799f77882d9bd13456c91be..84d1e574b8e7aff91c774a1035c75280cd8ac03c 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp @@ -8,7 +8,14 @@ #include "ftl/operators/opticalflow.hpp" #endif + +#include "ftl/operators/smoothing.hpp" +#include "ftl/operators/colours.hpp" +#include "ftl/operators/normals.hpp" +#include "ftl/operators/filling.hpp" +#include "ftl/operators/segmentation.hpp" #include "ftl/operators/disparity.hpp" +#include "ftl/operators/mask.hpp" #include "ftl/threads.hpp" #include "calibrate.hpp" @@ -132,6 +139,11 @@ void StereoVideoSource::init(const string &file) { #endif pipeline_depth_->append<ftl::operators::DisparityBilateralFilter>("bilateral_filter"); pipeline_depth_->append<ftl::operators::DisparityToDepth>("calculate_depth"); + pipeline_depth_->append<ftl::operators::ColourChannels>("colour"); // Convert BGR to BGRA + pipeline_depth_->append<ftl::operators::Normals>("normals"); // Estimate surface normals + pipeline_depth_->append<ftl::operators::CrossSupport>("cross"); + pipeline_depth_->append<ftl::operators::DiscontinuityMask>("discontinuity_mask"); + pipeline_depth_->append<ftl::operators::AggreMLS>("mls"); // Perform MLS (using smoothing channel) LOG(INFO) << "StereoVideo source ready..."; ready_ = true;