From 17ce179b109b316847846e5380e922495a301981 Mon Sep 17 00:00:00 2001 From: Nicolas Pope <nicolas.pope@utu.fi> Date: Mon, 8 Jun 2020 15:15:04 +0300 Subject: [PATCH] Support new basler cameras --- CMakeLists.txt | 2 + applications/gui/src/main.cpp | 8 + .../include/ftl/virtual_source.hpp | 2 +- applications/reconstruct/src/main.cpp | 1 - applications/vision/src/main.cpp | 25 ++ cmake/FindPylon.cmake | 31 +++ components/codecs/src/depth_convert.cu | 4 +- components/codecs/src/nvidia_decoder.cpp | 2 +- components/common/cpp/include/ftl/config.h.in | 1 + components/common/cpp/src/cuda_common.cpp | 3 + components/common/cpp/src/timer.cpp | 2 +- components/operators/src/colours.cpp | 4 +- components/operators/src/depth.cpp | 12 +- components/rgbd-sources/CMakeLists.txt | 13 +- .../rgbd-sources/include/ftl/rgbd/camera.hpp | 8 + .../include/ftl/rgbd/detail/abr.hpp | 121 --------- .../include/ftl/rgbd/detail/netframe.hpp | 50 ---- .../include/ftl/rgbd/detail/source.hpp | 75 ------ .../rgbd-sources/include/ftl/rgbd/group.hpp | 3 +- .../include/ftl/rgbd/snapshot.hpp | 116 -------- .../rgbd-sources/include/ftl/rgbd/source.hpp | 154 ++--------- .../include/ftl/rgbd/streamer.hpp | 187 ------------- .../rgbd-sources/include/ftl/rgbd/virtual.hpp | 28 -- .../rgbd-sources/include/ftl/rgbd_source.hpp | 94 ------- components/rgbd-sources/src/abr.cpp | 120 --------- components/rgbd-sources/src/basesource.hpp | 69 +++++ .../rgbd-sources/src/bitrate_settings.hpp | 12 - components/rgbd-sources/src/camera.cpp | 22 ++ components/rgbd-sources/src/disparity.cpp | 76 ------ components/rgbd-sources/src/disparity.hpp | 95 ------- components/rgbd-sources/src/group.cpp | 56 +--- components/rgbd-sources/src/source.cpp | 238 +++++------------ .../rgbd-sources/src/sources/image/image.hpp | 13 +- .../sources/middlebury/middlebury_source.cpp | 8 +- .../sources/middlebury/middlebury_source.hpp | 9 +- .../sources/realsense/realsense_source.cpp | 17 +- .../sources/realsense/realsense_source.hpp | 9 +- .../sources/screencapture/screencapture.cpp | 20 +- .../sources/screencapture/screencapture.hpp | 12 +- .../src/sources/snapshot/snapshot_source.cpp | 2 +- .../src/sources/snapshot/snapshot_source.hpp | 2 +- .../src/sources/stereovideo/calibrate.hpp | 1 - .../src/sources/stereovideo/device.hpp | 55 ++++ .../stereovideo/{local.cpp => opencv.cpp} | 23 +- .../stereovideo/{local.hpp => opencv.hpp} | 44 +-- .../src/sources/stereovideo/pylon.cpp | 250 ++++++++++++++++++ .../src/sources/stereovideo/pylon.hpp | 60 +++++ .../src/sources/stereovideo/stereovideo.cpp | 117 ++++---- .../src/sources/stereovideo/stereovideo.hpp | 18 +- components/rgbd-sources/test/source_unit.cpp | 61 ++--- components/streams/src/parsers.cpp | 10 +- components/streams/src/sender.cpp | 18 +- 52 files changed, 831 insertions(+), 1552 deletions(-) create mode 100644 cmake/FindPylon.cmake delete mode 100644 components/rgbd-sources/include/ftl/rgbd/detail/abr.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd/detail/netframe.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd/detail/source.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd/snapshot.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd/streamer.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd/virtual.hpp delete mode 100644 components/rgbd-sources/include/ftl/rgbd_source.hpp delete mode 100644 components/rgbd-sources/src/abr.cpp create mode 100644 components/rgbd-sources/src/basesource.hpp delete mode 100644 components/rgbd-sources/src/bitrate_settings.hpp delete mode 100644 components/rgbd-sources/src/disparity.cpp delete mode 100644 components/rgbd-sources/src/disparity.hpp create mode 100644 components/rgbd-sources/src/sources/stereovideo/device.hpp rename components/rgbd-sources/src/sources/stereovideo/{local.cpp => opencv.cpp} (94%) rename components/rgbd-sources/src/sources/stereovideo/{local.hpp => opencv.hpp} (50%) create mode 100644 components/rgbd-sources/src/sources/stereovideo/pylon.cpp create mode 100644 components/rgbd-sources/src/sources/stereovideo/pylon.hpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 90be9db69..3f2c96fb1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -48,6 +48,8 @@ find_package( URIParser REQUIRED ) find_package( MsgPack REQUIRED ) find_package( Eigen3 REQUIRED ) +find_package( Pylon ) + VERSION_STR_TO_INTS(OPENCV_MAJOR OPENCV_MINOR OPENCV_PATCH ${OpenCV_VERSION}) math(EXPR OPENCV_NUMBER "(${OPENCV_MAJOR} * 10000) + (${OPENCV_MINOR} * 100) + ${OPENCV_PATCH}") diff --git a/applications/gui/src/main.cpp b/applications/gui/src/main.cpp index 03146915e..182faf06e 100644 --- a/applications/gui/src/main.cpp +++ b/applications/gui/src/main.cpp @@ -10,8 +10,16 @@ #include <cuda_gl_interop.h> +#ifdef HAVE_PYLON +#include <pylon/PylonIncludes.h> +#endif + int main(int argc, char **argv) { +#ifdef HAVE_PYLON + Pylon::PylonAutoInitTerm autoInitTerm; +#endif + auto root = ftl::configure(argc, argv, "gui_default"); ftl::net::Universe *net = ftl::create<ftl::net::Universe>(root, "net"); diff --git a/applications/reconstruct/include/ftl/virtual_source.hpp b/applications/reconstruct/include/ftl/virtual_source.hpp index 931bdd5eb..b4162ef97 100644 --- a/applications/reconstruct/include/ftl/virtual_source.hpp +++ b/applications/reconstruct/include/ftl/virtual_source.hpp @@ -19,7 +19,7 @@ namespace rgbd { * calculating disparity, before converting to depth. Calibration of the images * is also performed. */ -class VirtualSource : public ftl::rgbd::detail::Source { +class VirtualSource : public ftl::rgbd::BaseSourceImpl { public: VirtualSource(ftl::rgbd::Source*); ~VirtualSource(); diff --git a/applications/reconstruct/src/main.cpp b/applications/reconstruct/src/main.cpp index fea482a24..5f37c0961 100644 --- a/applications/reconstruct/src/main.cpp +++ b/applications/reconstruct/src/main.cpp @@ -10,7 +10,6 @@ #include <ftl/configuration.hpp> #include <ftl/depth_camera.hpp> #include <ftl/rgbd.hpp> -#include <ftl/rgbd/virtual.hpp> #include <ftl/master.hpp> #include <ftl/rgbd/group.hpp> #include <ftl/threads.hpp> diff --git a/applications/vision/src/main.cpp b/applications/vision/src/main.cpp index 489a384b2..57606034b 100644 --- a/applications/vision/src/main.cpp +++ b/applications/vision/src/main.cpp @@ -34,6 +34,10 @@ #include "opencv2/highgui.hpp" #include "opencv2/core/utility.hpp" +#ifdef HAVE_PYLON +#include <pylon/PylonIncludes.h> +#endif + #ifdef WIN32 #pragma comment(lib, "Rpcrt4.lib") #endif @@ -193,12 +197,33 @@ static void run(ftl::Configurable *root) { delete net; } +static void threadSetCUDADevice() { + // Ensure all threads have correct cuda device + std::atomic<int> ijobs = 0; + for (int i=0; i<ftl::pool.size(); ++i) { + ftl::pool.push([&ijobs](int id) { + ftl::cuda::setDevice(); + ++ijobs; + while (ijobs < ftl::pool.size()) std::this_thread::sleep_for(std::chrono::milliseconds(10)); + }); + } + while (ijobs < ftl::pool.size()) std::this_thread::sleep_for(std::chrono::milliseconds(10)); +} + int main(int argc, char **argv) { + +#ifdef HAVE_PYLON + Pylon::PylonAutoInitTerm autoInitTerm; +#endif + #ifdef WIN32 SetPriorityClass(GetCurrentProcess(), HIGH_PRIORITY_CLASS); #endif std::cout << "FTL Vision Node " << FTL_VERSION_LONG << std::endl; auto root = ftl::configure(argc, argv, "vision_default"); + + // Use other GPU if available. + //ftl::cuda::setDevice(ftl::cuda::deviceCount()-1); std::cout << "Loading..." << std::endl; run(root); diff --git a/cmake/FindPylon.cmake b/cmake/FindPylon.cmake new file mode 100644 index 000000000..a9f69e004 --- /dev/null +++ b/cmake/FindPylon.cmake @@ -0,0 +1,31 @@ +############################################################################### +# Find Pylon +# + +set(PYLON_FOUND FALSE CACHE BOOL "" FORCE) + +if(WIN32) +find_path(PYLON_DIR NAMES include/pylon/PylonBase.h PATHS "C:/Program Files/Pylon" "C:/Program Files (x86)/Pylon") +else() +find_path(PYLON_DIR NAMES include/pylon/PylonBase.h PATHS "/opt/pylon" "/opt/pylon6") +endif() + +if (PYLON_DIR) + set(PYLON_FOUND TRUE CACHE BOOL "" FORCE) + set(HAVE_PYLON TRUE) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(Pylon DEFAULT_MSG PYLON_DIR) + + mark_as_advanced(PYLON_FOUND) + + list(APPEND PYLON_LIBRARIES pylonbase pylonutility GenApi_gcc_v3_1_Basler_pylon GCBase_gcc_v3_1_Basler_pylon) + + add_library(Pylon INTERFACE) + set_property(TARGET Pylon PROPERTY INTERFACE_INCLUDE_DIRECTORIES ${PYLON_DIR}/include) + #set_property(TARGET Pylon PROPERTY INTERFACE_LINK_DIRECTORIES ${PYLON_DIR}/lib) + link_directories(${PYLON_DIR}/lib) + set_property(TARGET Pylon PROPERTY INTERFACE_LINK_LIBRARIES ${PYLON_LIBRARIES}) +else() + add_library(Pylon INTERFACE) +endif() diff --git a/components/codecs/src/depth_convert.cu b/components/codecs/src/depth_convert.cu index 8b6bef8b5..81dc7d3bb 100644 --- a/components/codecs/src/depth_convert.cu +++ b/components/codecs/src/depth_convert.cu @@ -80,8 +80,8 @@ __global__ void depth_to_nv12_10_kernel(cv::cuda::PtrStepSz<float> depth, ushort luminance[(y+1)*pitch+x] = ushort(yuv3.x*255.0f) << 8; luminance[(y+1)*pitch+x+1] = ushort(yuv4.x*255.0f) << 8; - chroma[(y/2)*pitch+x] = ushort(Hb) << 8; - chroma[(y/2)*pitch+x+1] = ushort(Ha) << 8; + chroma[(y/2)*pitch+x] = ushort(Ha) << 8; + chroma[(y/2)*pitch+x+1] = ushort(Hb) << 8; } } diff --git a/components/codecs/src/nvidia_decoder.cpp b/components/codecs/src/nvidia_decoder.cpp index 3bda2c25b..0901e5188 100644 --- a/components/codecs/src/nvidia_decoder.cpp +++ b/components/codecs/src/nvidia_decoder.cpp @@ -177,7 +177,7 @@ bool NvidiaDecoder::decode(const ftl::codecs::Packet &pkt, cv::cuda::GpuMat &out height_ = nv_decoder_->GetHeight(); if (out.cols != ((is_float_frame && islossless) ? width_/2 : width_) || out.rows != height_) { - LOG(ERROR) << "Decoded frame not same size as buffer"; + LOG(ERROR) << "Decoded frame not same size as buffer: " << width_ << "x" << height_ << " -> " << out.cols << "x" << out.rows; return false; } diff --git a/components/common/cpp/include/ftl/config.h.in b/components/common/cpp/include/ftl/config.h.in index bb58bc207..99db4ca42 100644 --- a/components/common/cpp/include/ftl/config.h.in +++ b/components/common/cpp/include/ftl/config.h.in @@ -28,6 +28,7 @@ #cmakedefine HAVE_PORTAUDIO #cmakedefine HAVE_X11 #cmakedefine HAVE_OPUS +#cmakedefine HAVE_PYLON #cmakedefine ENABLE_PROFILER diff --git a/components/common/cpp/src/cuda_common.cpp b/components/common/cpp/src/cuda_common.cpp index 2eb5d19f8..ede4a998a 100644 --- a/components/common/cpp/src/cuda_common.cpp +++ b/components/common/cpp/src/cuda_common.cpp @@ -10,6 +10,8 @@ static int dev_count = 0; static std::vector<cudaDeviceProp> properties; bool ftl::cuda::initialise() { + if (dev_count > 0) return true; + // Do an initial CUDA check cudaSafeCall(cudaGetDeviceCount(&dev_count)); CHECK_GE(dev_count, 1) << "No CUDA devices found"; @@ -50,6 +52,7 @@ void ftl::cuda::setDevice(int id) { } void ftl::cuda::setDevice() { + LOG(INFO) << "Using CUDA Device " << dev_to_use; cudaSafeCall(cudaSetDevice(dev_to_use)); } diff --git a/components/common/cpp/src/timer.cpp b/components/common/cpp/src/timer.cpp index 7d1cc2b5f..bc8f97e2d 100644 --- a/components/common/cpp/src/timer.cpp +++ b/components/common/cpp/src/timer.cpp @@ -168,7 +168,7 @@ static void trigger_jobs() { j.job(ts); } const int64_t after = get_time(); - if (after - before > 0) LOG(WARNING) << "Precision jobs took too long (" << (after-before) << "ms)"; + if (after - before > 1) LOG(WARNING) << "Precision jobs took too long (" << (after-before) << "ms)"; // Then do also non-blocking swap callbacks for (auto &j : jobs[kTimerSwap]) { diff --git a/components/operators/src/colours.cpp b/components/operators/src/colours.cpp index 8ca2c62bf..610912076 100644 --- a/components/operators/src/colours.cpp +++ b/components/operators/src/colours.cpp @@ -49,7 +49,7 @@ bool ColourChannels::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStre in.createTexture<uchar4>(Channel::Right, true); } - if (in.hasChannel(Channel::Depth)) { + /*if (in.hasChannel(Channel::Depth)) { auto &depth = in.get<cv::cuda::GpuMat>(Channel::Depth); if (depth.size() != col.size()) { auto cvstream = cv::cuda::StreamAccessor::wrapStream(stream); @@ -71,7 +71,7 @@ bool ColourChannels::apply(ftl::rgbd::Frame &in, ftl::rgbd::Frame &out, cudaStre throw FTL_Error("Depth and colour channels and different resolutions: " << depth.size() << " vs " << right.size()); } } - } + }*/ return true; } diff --git a/components/operators/src/depth.cpp b/components/operators/src/depth.cpp index 24597a233..19696f67f 100644 --- a/components/operators/src/depth.cpp +++ b/components/operators/src/depth.cpp @@ -135,8 +135,10 @@ void DepthChannel::_createPipeline(size_t size) { if (pipe_ != nullptr) return; pipe_ = ftl::config::create<ftl::operators::Graph>(config(), "depth"); - depth_size_ = cv::Size( config()->value("width", 1280), - config()->value("height", 720)); + //depth_size_ = cv::Size( config()->value("width", 1280), + // config()->value("height", 720)); + + depth_size_ = cv::Size(0,0); pipe_->append<ftl::operators::ColourChannels>("colour"); // Convert BGR to BGRA pipe_->append<ftl::operators::CrossSupport>("cross"); @@ -168,6 +170,12 @@ bool DepthChannel::apply(ftl::rgbd::FrameSet &in, ftl::rgbd::FrameSet &out, cuda rbuf_.resize(in.frames.size()); + if (in.frames.size() > 0) { + if (depth_size_.width == 0) { + depth_size_ = in.firstFrame().get<cv::cuda::GpuMat>(Channel::Colour).size(); + } + } + for (size_t i=0; i<in.frames.size(); ++i) { if (!in.hasFrame(i)) continue; auto &f = in.frames[i]; diff --git a/components/rgbd-sources/CMakeLists.txt b/components/rgbd-sources/CMakeLists.txt index fafceea69..7e47d77e4 100644 --- a/components/rgbd-sources/CMakeLists.txt +++ b/components/rgbd-sources/CMakeLists.txt @@ -1,6 +1,6 @@ set(RGBDSRC src/sources/stereovideo/calibrate.cpp - src/sources/stereovideo/local.cpp + src/sources/stereovideo/opencv.cpp src/source.cpp src/frame.cpp src/frameset.cpp @@ -17,12 +17,9 @@ if (HAVE_REALSENSE) list(APPEND RGBDSRC "src/sources/realsense/realsense_source.cpp") endif() -if (LibArchive_FOUND) - list(APPEND RGBDSRC - src/sources/snapshot/snapshot.cpp - src/sources/snapshot/snapshot_source.cpp - ) -endif (LibArchive_FOUND) +if (HAVE_PYLON) + list(APPEND RGBDSRC "src/sources/stereovideo/pylon.cpp") +endif() add_library(ftlrgbd ${RGBDSRC}) @@ -38,7 +35,7 @@ if (CUDA_FOUND) set_property(TARGET ftlrgbd PROPERTY CUDA_SEPARABLE_COMPILATION OFF) endif() -target_link_libraries(ftlrgbd ftlcalibration ftlcommon ${OpenCV_LIBS} ${LIBSGM_LIBRARIES} ${CUDA_LIBRARIES} Eigen3::Eigen realsense ftlnet ${LibArchive_LIBRARIES} ftlcodecs ftloperators ftldata ${X11_X11_LIB} ${X11_Xext_LIB}) +target_link_libraries(ftlrgbd ftlcalibration ftlcommon ${OpenCV_LIBS} ${LIBSGM_LIBRARIES} ${CUDA_LIBRARIES} Eigen3::Eigen realsense ftlnet ${LibArchive_LIBRARIES} ftlcodecs ftloperators ftldata ${X11_X11_LIB} ${X11_Xext_LIB} Pylon) if (BUILD_TESTS) add_subdirectory(test) diff --git a/components/rgbd-sources/include/ftl/rgbd/camera.hpp b/components/rgbd-sources/include/ftl/rgbd/camera.hpp index edcff30bd..804a0c2d3 100644 --- a/components/rgbd-sources/include/ftl/rgbd/camera.hpp +++ b/components/rgbd-sources/include/ftl/rgbd/camera.hpp @@ -20,6 +20,14 @@ enum class Projection { EQUIRECTANGULAR = 2 }; +typedef unsigned int capability_t; + +static const capability_t kCapMovable = 0x0001; // A movable virtual cam +static const capability_t kCapVideo = 0x0002; // Is a video feed +static const capability_t kCapActive = 0x0004; // An active depth sensor +static const capability_t kCapStereo = 0x0008; // Has right RGB +static const capability_t kCapDepth = 0x0010; // Has depth capabilities + /** * All properties associated with cameras. This structure is designed to * operate on CPU and GPU. diff --git a/components/rgbd-sources/include/ftl/rgbd/detail/abr.hpp b/components/rgbd-sources/include/ftl/rgbd/detail/abr.hpp deleted file mode 100644 index b3d809784..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/detail/abr.hpp +++ /dev/null @@ -1,121 +0,0 @@ -#ifndef _FTL_RGBD_ABR_HPP_ -#define _FTL_RGBD_ABR_HPP_ - -#include <ftl/rgbd/detail/netframe.hpp> -#include <cstdint> - -namespace ftl { -namespace rgbd { -namespace detail { - -static const float kAspectRatio = 1.777778f; - -enum codec_t { - kCodecJPG = 0, - kCodecPNG -}; - -struct BitrateSetting { - int colour_res; - int depth_res; - int colour_qual; - int depth_qual; - codec_t colour_codec; - codec_t depth_codec; - int block_count_x; - - /*int width; - int height; - int jpg_quality; - int png_compression; - codec_t colour_codec; - codec_t depth_codec; - int chunking;*/ -}; - -static const BitrateSetting bitrate_settings[] = { - 1080, 1080, 95, 1, kCodecJPG, kCodecPNG, 4, - 1080, 720, 95, 1, kCodecJPG, kCodecPNG, 4, - 720, 720, 95, 1, kCodecJPG, kCodecPNG, 4, - 720, 576, 95, 5, kCodecJPG, kCodecPNG, 4, - 576, 576, 95, 5, kCodecJPG, kCodecPNG, 4, - 576, 480, 95, 5, kCodecJPG, kCodecPNG, 2, - 480, 480, 95, 5, kCodecJPG, kCodecPNG, 2, - 480, 360, 95, 9, kCodecJPG, kCodecPNG, 2, - 360, 360, 95, 9, kCodecJPG, kCodecPNG, 2, - 360, 360, 50, 9, kCodecJPG, kCodecPNG, 2 -}; - -/*static const BitrateSetting bitrate_settings[] = { - 1920, 1080, 95, 1, kCodecJPG, kCodecPNG, 4, // ? - 1280, 720, 95, 1, kCodecJPG, kCodecPNG, 4, // ~96Mbps - 1024, 576, 95, 5, kCodecJPG, kCodecPNG, 3, // ~62Mbps - 854, 480, 95, 5, kCodecJPG, kCodecPNG, 3, // ~48Mbps - 640, 360, 95, 9, kCodecJPG, kCodecPNG, 2, // ~31Mbps - 640, 360, 75, 9, kCodecJPG, kCodecPNG, 2, // ~25Mbps - 640, 360, 65, 9, kCodecJPG, kCodecPNG, 2, // ~24Mbps - 640, 360, 50, 9, kCodecJPG, kCodecPNG, 2, // ~23Mbps - 320, 160, 95, 9, kCodecJPG, kCodecPNG, 2, // ~10Mbps - 320, 160, 75, 9, kCodecJPG, kCodecPNG, 2 // ~8Mbps -};*/ - -typedef unsigned int bitrate_t; - -static const bitrate_t kBitrateBest = 0; -static const bitrate_t kBitrateWorst = 9; - -/** - * Adaptive Bitrate Controller to monitor and decide on a client streams - * bitrate. The basics of our approach are that if transmission latency exceeds - * some proportion of the frame time then mark it as a slow frame. Similarly if - * transmission latency falls below a proportion of frame time then mark it as - * a fast frame. If the net frame status is slow (thresholded) then reduce - * bitrate, if the net status is fast then increase bitrate. - */ -class ABRController { - public: - ABRController(); - ~ABRController(); - - /** - * From a received frame, select a bitrate based upon actual and required - * bitrate as well as past frames. - */ - bitrate_t selectBitrate(const ftl::rgbd::detail::NetFrame &); - - /** - * Called to tell the controller the new bitrate is now in use by the stream - */ - void notifyChanged(); - - void setMaximumBitrate(bitrate_t); - void setMinimumBitrate(bitrate_t); - - static const ftl::rgbd::detail::BitrateSetting &getBitrateInfo(bitrate_t b); - static int getColourWidth(bitrate_t b); - static int getDepthWidth(bitrate_t b); - static int getColourHeight(bitrate_t b); - static int getDepthHeight(bitrate_t b); - static int getBlockCountX(bitrate_t b); - static int getBlockCountY(bitrate_t b); - static int getBlockCount(bitrate_t b); - static int getColourQuality(bitrate_t b); - static int getDepthQuality(bitrate_t b); - - private: - unsigned int down_log_; // Bit log of delayed frames - unsigned int up_log_; // Bit log of fast frames - int64_t last_br_change_; // Time of last adaptive change - float down_threshold_; // Proportion of min bitrate before reduction - float up_threshold_; // Proportion of min bitrate before increase - bitrate_t bitrate_; - bool enabled_; - bitrate_t max_; - bitrate_t min_; -}; - -} -} -} - -#endif // _FTL_RGBD_ABR_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/detail/netframe.hpp b/components/rgbd-sources/include/ftl/rgbd/detail/netframe.hpp deleted file mode 100644 index 995848ff0..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/detail/netframe.hpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef _FTL_RGBD_NETFRAME_HPP_ -#define _FTL_RGBD_NETFRAME_HPP_ - -#include <cstdint> -#include <vector> -#include <ftl/rgbd/source.hpp> - -namespace ftl { -namespace rgbd { -namespace detail { - -/** - * Buffers for a single frame as it is being received over the network. - * Also maintains statistics about the frame transmission for later analysis. - */ -struct NetFrame { - cv::cuda::GpuMat channel[2]; - volatile int64_t timestamp; - std::atomic<int> chunk_count[2]; - std::atomic<int> channel_count; - int chunk_total[2]; - std::atomic<int> tx_size; - int64_t tx_latency; - MUTEX mtx; -}; - -/** - * Manage multiple frames with their timestamp as an identifier. Once a frame - * is completed it should be freed immediately from the queue for reuse. It - * is not the job of this queue to buffer frames for longer periods, see Group - * for this functionality. This queue is only to manage chunk ordering problems. - */ -class NetFrameQueue { - public: - explicit NetFrameQueue(int size=2); - ~NetFrameQueue(); - - NetFrame &getFrame(int64_t ts, const cv::Size &, int c1type, int c2type); - void freeFrame(NetFrame &); - - private: - std::vector<NetFrame> frames_; - MUTEX mtx_; -}; - -} -} -} - -#endif // _FTL_RGBD_NETFRAME_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp b/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp deleted file mode 100644 index a5949ff51..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/detail/source.hpp +++ /dev/null @@ -1,75 +0,0 @@ -#ifndef _FTL_RGBD_DETAIL_SOURCE_HPP_ -#define _FTL_RGBD_DETAIL_SOURCE_HPP_ - -#include <Eigen/Eigen> -#include <ftl/cuda_util.hpp> -//#include <opencv2/opencv.hpp> -#include <ftl/rgbd/camera.hpp> -#include <ftl/rgbd/frame.hpp> - -namespace ftl{ -namespace rgbd { - -class Source; - -typedef unsigned int capability_t; - -static const capability_t kCapMovable = 0x0001; // A movable virtual cam -static const capability_t kCapVideo = 0x0002; // Is a video feed -static const capability_t kCapActive = 0x0004; // An active depth sensor -static const capability_t kCapStereo = 0x0008; // Has right RGB -static const capability_t kCapDepth = 0x0010; // Has depth capabilities - - -namespace detail { - -class Source { - public: - friend class ftl::rgbd::Source; - - public: - explicit Source(ftl::rgbd::Source *host) : capabilities_(0), host_(host), params_(state_.getLeft()), timestamp_(0) { } - virtual ~Source() {} - - /** - * Perform hardware data capture. - */ - virtual bool capture(int64_t ts)=0; - - /** - * Perform IO operation to get the data. - */ - virtual bool retrieve()=0; - - /** - * Do any processing from previously captured frames... - * @param n Number of frames to request in batch. Default -1 means automatic (10) - * @param b Bit rate setting. -1 = automatic, 0 = best quality, 9 = lowest quality - */ - virtual bool compute(int n, int b)=0; - - /** - * Between frames, or before next frame, do any buffer swapping operations. - */ - virtual void swap() {} - - virtual bool isReady() { return false; }; - virtual void setPose(const Eigen::Matrix4d &pose) { state_.setPose(pose); }; - - virtual Camera parameters(ftl::codecs::Channel) { return params_; }; - - protected: - ftl::rgbd::FrameState state_; - capability_t capabilities_; - ftl::rgbd::Source *host_; - ftl::rgbd::Camera ¶ms_; - ftl::rgbd::Frame frame_; - int64_t timestamp_; - //Eigen::Matrix4d &pose_; -}; - -} -} -} - -#endif // _FTL_RGBD_DETAIL_SOURCE_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/group.hpp b/components/rgbd-sources/include/ftl/rgbd/group.hpp index b339511a2..eed75bbc5 100644 --- a/components/rgbd-sources/include/ftl/rgbd/group.hpp +++ b/components/rgbd-sources/include/ftl/rgbd/group.hpp @@ -103,6 +103,7 @@ class Group : public ftl::rgbd::Generator { ftl::operators::Graph *pipeline_; std::atomic<int> jobs_; + std::atomic<int> cjobs_; volatile bool skip_; ftl::timer::TimerHandle cap_id_; ftl::timer::TimerHandle swap_id_; @@ -111,7 +112,7 @@ class Group : public ftl::rgbd::Generator { MUTEX mutex_; void _retrieveJob(ftl::rgbd::Source *); - void _computeJob(ftl::rgbd::Source *); + void _dispatchJob(ftl::rgbd::Source *, int64_t); }; } diff --git a/components/rgbd-sources/include/ftl/rgbd/snapshot.hpp b/components/rgbd-sources/include/ftl/rgbd/snapshot.hpp deleted file mode 100644 index 8e1fa5960..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/snapshot.hpp +++ /dev/null @@ -1,116 +0,0 @@ -#pragma once -#ifndef _FTL_RGBD_SNAPSHOT_HPP_ -#define _FTL_RGBD_SNAPSHOT_HPP_ - -#include <loguru.hpp> -#include <thread> - -#include <opencv2/core/mat.hpp> - -#include <Eigen/Eigen> -#include <opencv2/core/eigen.hpp> - -#include <ftl/rgbd/source.hpp> -#include <ftl/rgbd/camera.hpp> - -#include <atomic> -#include <archive.h> -#include <archive_entry.h> - -namespace ftl { -namespace rgbd { - -// FIXME: NOT thread safe - -class SnapshotWriter { -public: - explicit SnapshotWriter(const std::string &filename); - ~SnapshotWriter(); - - void addSource(const std::string &id, const ftl::rgbd::Camera ¶ms, const Eigen::Matrix4d &extrinsic); - void addSource(const std::string &id, const std::vector<double> ¶ms, const cv::Mat &extrinsic); - bool addRGBD(size_t source, const cv::Mat &rgb, const cv::Mat &depth, uint64_t time=0); - - bool addMat(const std::string &name, const cv::Mat &mat, const std::string &format, const std::vector<int> ¶ms); - bool addFile(const std::string &name, const std::vector<uchar> &buf); - bool addFile(const std::string &name, const uchar *buf, const size_t len); - - void writeIndex(); - -private: - std::vector<std::string> sources_; - std::vector<std::vector<double>> params_; - std::vector<cv::Mat> extrinsic_; - std::vector<size_t> frame_idx_; - std::vector<std::vector<std::string>> fname_rgb_; - std::vector<std::vector<std::string>> fname_depth_; - - struct archive *archive_ = nullptr; - struct archive_entry *entry_ = nullptr; -}; - -class SnapshotStreamWriter { -public: - SnapshotStreamWriter(const std::string &filename, int delay); - ~SnapshotStreamWriter(); - void addSource(ftl::rgbd::Source* src); - void start(); - void stop(); - -private: - std::atomic<bool> run_; - bool finished_; - int delay_; - - std::vector<ftl::rgbd::Source*> sources_; - SnapshotWriter writer_; - std::thread thread_; - - void run(); -}; - -class Snapshot { -public: - size_t getSourcesCount(); - size_t getFramesCount(); - - std::string getSourceURI(size_t camera); - ftl::rgbd::Camera getParameters(size_t camera); - void getPose(size_t camera, cv::Mat &out); - void getPose(size_t camera, Eigen::Matrix4d &out); - - void getLeftRGB(size_t camera, size_t frame, cv::Mat &data); - void getLeftDepth(size_t camera, size_t frame, cv::Mat &data); - - size_t n_frames; - size_t n_cameras; - - std::vector<std::string> sources; - std::vector<ftl::rgbd::Camera> parameters; - std::vector<cv::Mat> extrinsic; - std::vector<std::vector<cv::Mat>> rgb_left; - std::vector<std::vector<cv::Mat>> depth_left; -}; - -class SnapshotReader { -public: - explicit SnapshotReader(const std::string &filename); - ~SnapshotReader(); - - Snapshot readArchive(); - -private: - bool readEntry(std::vector<uchar> &data); - - bool getDepth(const std::string &name, cv::Mat &data); - bool getRGB(const std::string &name, cv::Mat &data); - - std::map<std::string, std::vector<uchar>> files_; - struct archive *archive_; - struct archive_entry *entry_; -}; - -}; -}; - -#endif // _FTL_RGBD_SNAPSHOT_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/source.hpp b/components/rgbd-sources/include/ftl/rgbd/source.hpp index 5676c25d3..868e1a9a0 100644 --- a/components/rgbd-sources/include/ftl/rgbd/source.hpp +++ b/components/rgbd-sources/include/ftl/rgbd/source.hpp @@ -7,8 +7,6 @@ #include <ftl/net/universe.hpp> #include <ftl/uri.hpp> #include <ftl/rgbd/camera.hpp> -#include <ftl/rgbd/detail/source.hpp> -#include <ftl/codecs/packet.hpp> #include <opencv2/core/mat.hpp> #include <Eigen/Eigen> #include <string> @@ -25,15 +23,11 @@ class Universe; namespace rgbd { -static inline bool isValidDepth(float d) { return (d > 0.01f) && (d < 39.99f); } - -class SnapshotReader; -class VirtualSource; -class Player; - -typedef std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> RawCallback; +class BaseSourceImpl; typedef std::function<void(int64_t,ftl::rgbd::Frame&)> FrameCallback; +static inline bool isValidDepth(float d) { return (d > 0.01f) && (d < 39.99f); } + /** * RGBD Generic data source configurable entity. This class hides the * internal implementation of an RGBD source by providing accessor functions @@ -58,7 +52,6 @@ class Source : public ftl::Configurable { protected: explicit Source(ftl::config::json_t &cfg); - Source(ftl::config::json_t &cfg, ftl::rgbd::SnapshotReader *); Source(ftl::config::json_t &cfg, ftl::net::Universe *net); virtual ~Source(); @@ -66,7 +59,7 @@ class Source : public ftl::Configurable { /** * Is this source valid and ready to grab?. */ - bool isReady() { return (impl_) ? impl_->isReady() : false; } + bool isReady(); /** * Change the second channel source. @@ -89,53 +82,31 @@ class Source : public ftl::Configurable { */ bool retrieve(); + /** + * Generate a thread job using the provided callback for the most recently + * retrieved frame (matching the provided timestamp). If already busy + * dispatching, returns false. + */ + bool dispatch(int64_t ts); + /** * Between frames, do any required buffer swaps. */ - void swap() { if (impl_) impl_->swap(); } + //void swap() { if (impl_) impl_->swap(); } /** * Do any post-grab processing. This function * may take considerable time to return, especially for sources requiring * software stereo correspondance. */ - bool compute(int N=-1, int B=-1); - - /** - * Wrapper grab that performs capture, swap and computation steps in one. - * It is more optimal to perform capture and compute in parallel. - */ - bool grab(int N=-1, int B=-1) { - bool c = capture(0); - c = c && retrieve(); - swap(); - return c && compute(N,B); - } - - /** - * Get a copy of both colour and depth frames. Note that this does a buffer - * swap rather than a copy, so the parameters should be persistent buffers for - * best performance. - */ - [[deprecated]] void getFrames(cv::Mat &c, cv::Mat &d); - - /** - * Directly upload source RGB and Depth to GPU. - */ - void upload(cv::cuda::GpuMat&, cv::cuda::GpuMat&); - - void uploadColour(cv::cuda::GpuMat&); - void uploadDepth(cv::cuda::GpuMat&); + //bool compute(int64_t ts); //bool isVirtual() const { return impl_ == nullptr; } /** * Get the source's camera intrinsics. */ - const Camera ¶meters() const { - if (impl_) return impl_->params_; - else throw FTL_Error("Cannot get parameters for bad source"); - } + const Camera ¶meters() const; /** * Get camera intrinsics for another channel. For example the right camera @@ -152,30 +123,23 @@ class Source : public ftl::Configurable { */ virtual void setPose(const Eigen::Matrix4d &pose); - /** - * Get the camera position as a pose matrix. - */ - [[deprecated]] const Eigen::Matrix4d &getPose() const; - /** * Check what features this source has available. */ - bool hasCapabilities(capability_t); + [[deprecated]] bool hasCapabilities(capability_t); - capability_t getCapabilities() const; + [[deprecated]] capability_t getCapabilities() const; /** * Force the internal implementation to be reconstructed. */ void reset(); - ftl::net::Universe *getNet() const { return net_; } + [[deprecated]] ftl::net::Universe *getNet() const { return net_; } std::string getURI() { return value("uri", std::string("")); } - ftl::rgbd::FrameState &state() { return impl_->state_; } - - //void customImplementation(detail::Source *); + ftl::rgbd::FrameState &state(); SHARED_MUTEX &mutex() { return mutex_; } @@ -189,98 +153,30 @@ class Source : public ftl::Configurable { void setCallback(const FrameCallback &cb); void removeCallback() { callback_ = nullptr; } - /** - * Add a callback to immediately receive any raw data from this source. - * Currently this only works for a net source since other sources don't - * produce raw encoded data. - */ - void addRawCallback(const RawCallback &); - - /** - * THIS DOES NOT WORK CURRENTLY. - */ - void removeRawCallback(const RawCallback &); - - /** - * INTERNAL. Used to send raw data to callbacks. - */ - void notifyRaw(const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt); - /** * Notify of a decoded or available pair of frames. This calls the source * callback after having verified the correct resolution of the frames. */ //void notify(int64_t ts, cv::cuda::GpuMat &c1, cv::cuda::GpuMat &c2); - void notify(int64_t ts, ftl::rgbd::Frame &f); + //void notify(int64_t ts, ftl::rgbd::Frame &f); - // ==== Inject Data into stream ============================================ - /** - * Generate a stream packet with arbitrary data. The data is packed using - * msgpack and is given the timestamp of the most recent frame. - */ - template <typename... ARGS> - void inject(ftl::codecs::Channel c, ARGS... args); - - void inject(const Eigen::Matrix4d &pose); - - protected: - detail::Source *impl_; + private: + BaseSourceImpl *impl_; Eigen::Matrix4d pose_; ftl::net::Universe *net_; SHARED_MUTEX mutex_; ftl::codecs::Channel channel_; cudaStream_t stream_; FrameCallback callback_; - std::list<RawCallback> rawcallbacks_; - - detail::Source *_createImplementation(); - detail::Source *_createFileImpl(const ftl::URI &uri); - detail::Source *_createNetImpl(const ftl::URI &uri); - detail::Source *_createDeviceImpl(const ftl::URI &uri); - - static ftl::rgbd::Player *__createReader(const std::string &path); + ftl::rgbd::Frame frames_[2]; + bool is_dispatching; + bool is_retrieving; - static std::map<std::string, ftl::rgbd::Player*> readers__; + void _swap(); }; } } -class VectorBuffer { - public: - inline explicit VectorBuffer(std::vector<unsigned char> &v) : vector_(v) {} - - inline void write(const char *data, std::size_t size) { - vector_.insert(vector_.end(), (const unsigned char*)data, (const unsigned char*)data+size); - } - - private: - std::vector<unsigned char> &vector_; -}; - -template <typename... ARGS> -void ftl::rgbd::Source::inject(ftl::codecs::Channel c, ARGS... args) { - if (!impl_) return; - auto data = std::make_tuple(args...); - - ftl::codecs::StreamPacket spkt; - ftl::codecs::Packet pkt; - - spkt.timestamp = impl_->timestamp_; - spkt.channel = c; - spkt.frame_number = 0; - spkt.streamID = 0; - pkt.codec = ftl::codecs::codec_t::MSGPACK; - pkt.bitrate = 0; - pkt.frame_count = 1; - //pkt.definition = ftl::codecs::definition_t::Any; - pkt.flags = 0; - - VectorBuffer buf(pkt.data); - msgpack::pack(buf, data); - - notifyRaw(spkt, pkt); -} - #endif // _FTL_RGBD_SOURCE_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/streamer.hpp b/components/rgbd-sources/include/ftl/rgbd/streamer.hpp deleted file mode 100644 index f6fc1a044..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/streamer.hpp +++ /dev/null @@ -1,187 +0,0 @@ -#ifndef _FTL_RGBD_STREAMER_HPP_ -#define _FTL_RGBD_STREAMER_HPP_ - -#include <loguru.hpp> -#include <ftl/configuration.hpp> -#include <ftl/configurable.hpp> -#include <ftl/rgbd/source.hpp> -#include <ftl/rgbd/group.hpp> -#include <ftl/net/universe.hpp> -#include <ftl/codecs/encoder.hpp> -#include <ftl/threads.hpp> -#include <string> -#include <vector> -#include <map> -#include <atomic> - -namespace ftl { -namespace rgbd { - -//static const int kChunkDim = 4; -//static constexpr int kChunkCount = kChunkDim * kChunkDim; - -namespace detail { - -struct StreamClient { - std::string uri; - ftl::UUID peerid; - std::atomic<int> txcount; // Frames sent since last request - int txmax; // Frames to send in request - ftl::codecs::preset_t preset; -}; - -static const unsigned int kGrabbed = 0x1; -static const unsigned int kRGB = 0x2; -static const unsigned int kDepth = 0x4; - -static const unsigned int kFrameDropLimit = 5; -static const unsigned int kMaxBitrateLevels = 10; - -struct StreamSource { - ftl::rgbd::Source *src; - std::atomic<int> jobs; // Busy or ready to swap? - std::atomic<unsigned int> clientCount; - - int hq_count; // Number of high quality requests - int lq_count; // Number of low quality requests - ftl::codecs::preset_t hq_bitrate=ftl::codecs::kPresetBest; // Max bitrate - ftl::codecs::preset_t lq_bitrate=ftl::codecs::kPresetWorst; // Min bitrate - - cv::Mat rgb; // Tx buffer - cv::Mat depth; // Tx buffer - cv::Mat prev_rgb; - cv::Mat prev_depth; - std::list<detail::StreamClient> clients; - SHARED_MUTEX mutex; - unsigned long long frame; - int id; - - ftl::codecs::Encoder *hq_encoder_c1 = nullptr; - ftl::codecs::Encoder *hq_encoder_c2 = nullptr; - ftl::codecs::Encoder *lq_encoder_c1 = nullptr; - ftl::codecs::Encoder *lq_encoder_c2 = nullptr; -}; - -} - -/** - * The maximum number of frames a client can request in a single request. - */ -static const int kMaxFrames = 100; - -enum encoder_t { - kEncodeVideo, - kEncodeImages -}; - -/** - * Allows network streaming of a number of RGB-Depth sources. Remote machines - * can discover available streams from an instance of Streamer. It also allows - * for adaptive bitrate streams where bandwidth can be monitored and different - * data rates can be requested, it is up to the remote machine to decide on - * desired bitrate. - * - * The capture and compression steps operate in different threads and each - * source and bitrate also operate on different threads. For a specific source - * and specific bitrate there is a single thread that sends data to all - * requesting clients. - * - * Use ftl::create<Streamer>(parent, name) to construct, don't construct - * directly. - * - * Note that the streamer attempts to maintain a fixed frame rate by - * monitoring job processing times and sleeping if there is spare time. - */ -class Streamer : public ftl::Configurable { - public: - [[deprecated]] Streamer(nlohmann::json &config, ftl::net::Universe *net); - ~Streamer(); - - /** - * Add an RGB-Depth source to be made available for streaming. - */ - void add(Source *); - - /** - * Allow all sources in another group to be proxy streamed by this streamer. - */ - void add(ftl::rgbd::Group *grp); - - ftl::rgbd::Group *group() { return &group_; } - - void remove(Source *); - void remove(const std::string &); - - /** - * Enable the streaming. This creates the threads, and if block is false - * then another thread will manage the stream process. - */ - void run(bool block=false); - - /** - * Terminate all streaming and join the threads. - */ - void stop(); - - void wait(); - - /** - * Alternative to calling run(), it will operate a single frame capture, - * compress and stream cycle. - */ - void poll(); - - Source *get(const std::string &uri); - - private: - ftl::rgbd::Group group_; - std::map<std::string, detail::StreamSource*> sources_; - std::vector<detail::StreamSource*> sourcesByNum_; - std::list<ftl::rgbd::Group*> proxy_grps_; - //ctpl::thread_pool pool_; - SHARED_MUTEX mutex_; - bool active_; - ftl::net::Universe *net_; - bool late_; - int compress_level_; - int64_t clock_adjust_; - ftl::UUID time_peer_; - int64_t last_frame_; - int64_t frame_no_; - bool insert_iframes_; - - ftl::codecs::Channel second_channel_; - - int64_t mspf_; - float actual_fps_; - //int64_t last_dropped_; - //int drop_count_; - - ftl::timer::TimerHandle timer_job_; - - ftl::codecs::device_t hq_devices_; - ftl::codecs::codec_t hq_codec_; - - enum class Quality { - High, - Low, - Any - }; - - void _process(ftl::rgbd::FrameSet &); - void _cleanUp(); - void _addClient(const std::string &source, int N, int rate, const ftl::UUID &peer, const std::string &dest); - void _transmitPacket(detail::StreamSource *src, const ftl::codecs::Packet &pkt, ftl::codecs::Channel chan, bool hasChan2, Quality q); - void _transmitPacket(detail::StreamSource *src, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt, Quality q); - - //void _encodeHQAndTransmit(detail::StreamSource *src, const cv::Mat &, const cv::Mat &, int chunk); - //void _encodeLQAndTransmit(detail::StreamSource *src, const cv::Mat &, const cv::Mat &, int chunk); - //void _encodeAndTransmit(detail::StreamSource *src, ftl::codecs::Encoder *enc1, ftl::codecs::Encoder *enc2, const cv::Mat &, const cv::Mat &); - //void _encodeImageChannel1(const cv::Mat &in, std::vector<unsigned char> &out, unsigned int b); - //bool _encodeImageChannel2(const cv::Mat &in, std::vector<unsigned char> &out, ftl::codecs::Channel_t c, unsigned int b); -}; - -} -} - -#endif // _FTL_RGBD_STREAMER_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd/virtual.hpp b/components/rgbd-sources/include/ftl/rgbd/virtual.hpp deleted file mode 100644 index f9bf5e7f5..000000000 --- a/components/rgbd-sources/include/ftl/rgbd/virtual.hpp +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef _FTL_RGBD_VIRTUAL_HPP_ -#define _FTL_RGBD_VIRTUAL_HPP_ - -#include <ftl/rgbd/source.hpp> - -namespace ftl { -namespace rgbd { - -class VirtualSource : public ftl::rgbd::Source { - public: - explicit VirtualSource(ftl::config::json_t &cfg); - ~VirtualSource(); - - void onRender(const std::function<bool(ftl::rgbd::Frame &)> &); - - /** - * Write frames into source buffers from an external renderer. Virtual - * sources do not have an internal generator of frames but instead have - * their data provided from an external rendering class. This function only - * works when there is no internal generator. - */ - //void write(int64_t ts, ftl::rgbd::Frame &frame, cudaStream_t stream=0); -}; - -} -} - -#endif // _FTL_RGBD_VIRTUAL_HPP_ diff --git a/components/rgbd-sources/include/ftl/rgbd_source.hpp b/components/rgbd-sources/include/ftl/rgbd_source.hpp deleted file mode 100644 index c065e6e19..000000000 --- a/components/rgbd-sources/include/ftl/rgbd_source.hpp +++ /dev/null @@ -1,94 +0,0 @@ -#pragma once -#ifndef _FTL_RGBD_SOURCE_HPP_ -#define _FTL_RGBD_SOURCE_HPP_ - -#include <ftl/config.h> -#include <ftl/configurable.hpp> -#include <ftl/threads.hpp> -#include <ftl/camera_params.hpp> -#include <ftl/net/universe.hpp> -#include <opencv2/opencv.hpp> -#include <Eigen/Eigen> - -namespace ftl { -namespace rgbd { - -/** - * Abstract class for any generic RGB-Depth data source. It can also store pose - * information, although this must be provided by an external source. - */ -class RGBDSource : public ftl::Configurable { - public: - explicit RGBDSource(nlohmann::json &config); - RGBDSource(nlohmann::json &config, ftl::net::Universe *net); - virtual ~RGBDSource(); - - virtual void grab()=0; - virtual bool isReady(); - - void getRGBD(cv::Mat &rgb, cv::Mat &depth); - - const CameraParameters &getParameters() { return params_; }; - std::string getURI() const { return config_["$id"].get<std::string>(); } - - virtual void setPose(const Eigen::Matrix4f &pose) { pose_ = pose; }; - const Eigen::Matrix4f &getPose() { return pose_; }; - - virtual void reset() {} - - /** - * Get a point in camera coordinates at specified pixel location. - */ - Eigen::Vector4f point(uint x, uint y); - - /** - * Save the current RGB and Depth images to image files (jpg and png) with - * the specified file prefix (excluding file extension). - */ - bool snapshot(const std::string &fileprefix); - - /** - * Generate a video of this RGB-D source. - */ - //bool record(const std::string &filename); - - /** - * Factory registration class. - */ - class Register { - public: - // cppcheck-suppress * - Register(const std::string &n, std::function<RGBDSource*(nlohmann::json&,ftl::net::Universe*)> f) { - RGBDSource::_register(n,f); - }; - }; - - /** - * Factory instance creator where config contains a "type" property - * used as the instance name to construct. - */ - static RGBDSource *create(nlohmann::json &config, ftl::net::Universe *net); - - static void init(); - - protected: - static void _register(const std::string &n, std::function<RGBDSource*(nlohmann::json&,ftl::net::Universe*)> f); - - protected: - CameraParameters params_; - ftl::net::Universe *net_; - MUTEX mutex_; - cv::Mat rgb_; - cv::Mat depth_; - - private: - Eigen::Matrix4f pose_ = Eigen::Matrix4f::Identity(); - - private: - static std::map<std::string,std::function<RGBDSource*(nlohmann::json&,ftl::net::Universe*)>> *sources__; -}; - -}; -}; - -#endif // _FTL_RGBD_SOURCE_HPP_ diff --git a/components/rgbd-sources/src/abr.cpp b/components/rgbd-sources/src/abr.cpp deleted file mode 100644 index d387cde26..000000000 --- a/components/rgbd-sources/src/abr.cpp +++ /dev/null @@ -1,120 +0,0 @@ -#include <ftl/rgbd/detail/abr.hpp> -#include <ftl/timer.hpp> - -#include <bitset> - -using ftl::rgbd::detail::BitrateSetting; -using ftl::rgbd::detail::ABRController; -using ftl::rgbd::detail::bitrate_t; -using ftl::rgbd::detail::kBitrateWorst; -using ftl::rgbd::detail::kBitrateBest; -using ftl::rgbd::detail::bitrate_settings; -using ftl::rgbd::detail::NetFrame; - -ABRController::ABRController() { - bitrate_ = 0; - enabled_ = true; - max_ = kBitrateBest; - min_ = kBitrateWorst; -} - -ABRController::~ABRController() { - -} - -void ABRController::setMaximumBitrate(bitrate_t b) { - max_ = (b == -1) ? kBitrateBest : b; - if (bitrate_ < max_) bitrate_ = max_; -} - -void ABRController::setMinimumBitrate(bitrate_t b) { - min_ = (b == -1) ? kBitrateWorst : b; - if (bitrate_ > min_) bitrate_ = min_; -} - -void ABRController::notifyChanged() { - enabled_ = true; -} - -bitrate_t ABRController::selectBitrate(const NetFrame &frame) { - if (!enabled_) return bitrate_; - - float actual_mbps = (float(frame.tx_size) * 8.0f * (1000.0f / float(frame.tx_latency))) / 1048576.0f; - float min_mbps = (float(frame.tx_size) * 8.0f * (1000.0f / float(ftl::timer::getInterval()))) / 1048576.0f; - //if (actual_mbps < min_mbps) LOG(WARNING) << "Bitrate = " << actual_mbps << "Mbps, min required = " << min_mbps << "Mbps"; - float ratio = actual_mbps / min_mbps; - //LOG(INFO) << "Rate Ratio = " << frame.tx_latency; - - return bitrate_; - - down_log_ = down_log_ << 1; - up_log_ = up_log_ << 1; - - if (ratio < 1.2f) { - down_log_ += 1; - } else if (ratio > 1.5f) { - up_log_ += 1; - } - - std::bitset<32> bd(down_log_); - std::bitset<32> bu(up_log_); - - if (bitrate_ < min_ && int(bd.count()) - int(bu.count()) > 5) { - enabled_ = false; - down_log_ = 0; - up_log_ = 0; - bitrate_++; - LOG(INFO) << "Bitrate down to: " << bitrate_; - } else if (bitrate_ > max_ && int(bu.count()) - int(bd.count()) > 15) { - enabled_ = false; - up_log_ = 0; - down_log_ = 0; - bitrate_--; - LOG(INFO) << "Bitrate up to: " << bitrate_; - } - - return bitrate_; -} - -const BitrateSetting &ABRController::getBitrateInfo(bitrate_t b) { - if (b > kBitrateWorst) return bitrate_settings[kBitrateWorst]; - if (b < kBitrateBest) return bitrate_settings[kBitrateBest]; - return bitrate_settings[b]; -}; - -int ABRController::getColourWidth(bitrate_t b) { - return int(std::ceil(bitrate_settings[b].colour_res * kAspectRatio)) & 0x7FFFFFFFC; -} - -int ABRController::getDepthWidth(bitrate_t b) { - return std::ceil(bitrate_settings[b].depth_res * kAspectRatio); -} - -int ABRController::getColourHeight(bitrate_t b) { - return bitrate_settings[b].colour_res; -} - -int ABRController::getDepthHeight(bitrate_t b) { - return bitrate_settings[b].depth_res; -} - -int ABRController::getBlockCountX(bitrate_t b) { - return bitrate_settings[b].block_count_x; -} - -int ABRController::getBlockCountY(bitrate_t b) { - return bitrate_settings[b].block_count_x; -} - -int ABRController::getBlockCount(bitrate_t b) { - const int c = bitrate_settings[b].block_count_x; - return c*c; -} - -int ABRController::getColourQuality(bitrate_t b) { - return bitrate_settings[b].colour_qual; -} - -int ABRController::getDepthQuality(bitrate_t b) { - return bitrate_settings[b].depth_qual; -} diff --git a/components/rgbd-sources/src/basesource.hpp b/components/rgbd-sources/src/basesource.hpp new file mode 100644 index 000000000..e3996d8af --- /dev/null +++ b/components/rgbd-sources/src/basesource.hpp @@ -0,0 +1,69 @@ +#ifndef _FTL_RGBD_DETAIL_SOURCE_HPP_ +#define _FTL_RGBD_DETAIL_SOURCE_HPP_ + +#include <Eigen/Eigen> +#include <ftl/cuda_util.hpp> +#include <ftl/rgbd/camera.hpp> +#include <ftl/rgbd/frame.hpp> + +namespace ftl{ +namespace rgbd { + +class Source; + +/** + * Base class for source device implementations. Each device provides a capture + * and retrieve functionality. `capture` is called with a high resolution timer + * at a precise timestamp to ensure synchronisation. In another thread the + * `retrieve` function is called after `capture` to download any data into the + * provided frame object. The frame object is then dispatched for further + * processing, such as disparity calculation, or is discarded if a previous + * processing dispatch is still on going. + * + * @see ftl::rgbd::Group + */ +class BaseSourceImpl { + public: + // TODO: Remove this + friend class ftl::rgbd::Source; + + public: + explicit BaseSourceImpl(ftl::rgbd::Source *host) : capabilities_(0), host_(host), params_(state_.getLeft()) { } + virtual ~BaseSourceImpl() {} + + /** + * Perform hardware data capture. This should be low latency (<1ms). + */ + virtual bool capture(int64_t ts)=0; + + /** + * Perform slow IO operation to get the data into the given frame object. + * This can take up to 1 fps (eg. ~40ms), but should be faster. It occurs + * in a different thread to the `capture` call but will never occur at the + * same time as `capture`. If `capture` fails then this will not be called. + */ + virtual bool retrieve(ftl::rgbd::Frame &frame)=0; + + /** + * Is the source ready to capture and retrieve? + */ + virtual bool isReady() { return false; }; + + // These should be accessed via the state object in a frame. + [[deprecated]] virtual void setPose(const Eigen::Matrix4d &pose) { state_.setPose(pose); }; + [[deprecated]] virtual Camera parameters(ftl::codecs::Channel) { return params_; }; + + ftl::rgbd::Source *host() { return host_; } + ftl::rgbd::FrameState &state() { return state_; } + + protected: + ftl::rgbd::FrameState state_; + capability_t capabilities_; // To be deprecated + ftl::rgbd::Source *host_; + ftl::rgbd::Camera ¶ms_; +}; + +} +} + +#endif // _FTL_RGBD_DETAIL_SOURCE_HPP_ diff --git a/components/rgbd-sources/src/bitrate_settings.hpp b/components/rgbd-sources/src/bitrate_settings.hpp deleted file mode 100644 index 3dbd23bc1..000000000 --- a/components/rgbd-sources/src/bitrate_settings.hpp +++ /dev/null @@ -1,12 +0,0 @@ -#ifndef _FTL_RGBD_BITRATESETTINGS_HPP_ -#define _FTL_RGBD_BITRATESETTINGS_HPP_ - -namespace ftl { -namespace rgbd { -namespace detail { - -} -} -} - -#endif // _FTL_RGBD_BITRATESETTINGS_HPP_ diff --git a/components/rgbd-sources/src/camera.cpp b/components/rgbd-sources/src/camera.cpp index 96ac0be4c..b4631a69d 100644 --- a/components/rgbd-sources/src/camera.cpp +++ b/components/rgbd-sources/src/camera.cpp @@ -25,3 +25,25 @@ cv::Mat Camera::getCameraMatrix() const { K.at<double>(1,2) = -cy; return K; } + +/* + * Scale camera parameters to match resolution. + */ +Camera Camera::scaled(int width, int height) const { + const auto &cam = *this; + float scaleX = (float)width / (float)cam.width; + float scaleY = (float)height / (float)cam.height; + + //CHECK( abs(scaleX - scaleY) < 0.00000001f ); + + Camera newcam = cam; + newcam.width = width; + newcam.height = height; + newcam.fx *= scaleX; + newcam.fy *= scaleY; + newcam.cx *= scaleX; + newcam.cy *= scaleY; + newcam.doffs *= scaleX; + + return newcam; +} diff --git a/components/rgbd-sources/src/disparity.cpp b/components/rgbd-sources/src/disparity.cpp deleted file mode 100644 index 7d9089c1a..000000000 --- a/components/rgbd-sources/src/disparity.cpp +++ /dev/null @@ -1,76 +0,0 @@ -/* - * Copyright 2019 Nicolas Pope - */ - -#include "disparity.hpp" -#include <loguru.hpp> -#include <ftl/config.h> -#include <ftl/configuration.hpp> - -using ftl::rgbd::detail::Disparity; - -std::map<std::string, std::function<Disparity*(ftl::Configurable *, const std::string &)>> - *Disparity::algorithms__ = nullptr; - -Disparity::Disparity(nlohmann::json &config) - : ftl::Configurable(config), - min_disp_(value("minimum",0)), - max_disp_(value("maximum", 256)), - size_(value("width", 1280), value("height", 720)) - { - - } - -Disparity *Disparity::create(ftl::Configurable *parent, const std::string &name) { - nlohmann::json &config = ftl::config::resolve((!parent->getConfig()[name].is_null()) ? parent->getConfig()[name] : ftl::config::resolve(parent->getConfig())[name]); // ftl::config::resolve(parent->getConfig()[name]); - - //auto alg = parent->get<std::string>("algorithm"); - if (!config["algorithm"].is_string()) { - return nullptr; - } - std::string alg = config["algorithm"].get<std::string>(); - - if (algorithms__->count(alg) != 1) return nullptr; - return (*algorithms__)[alg](parent, name); -} - -void Disparity::_register(const std::string &n, - std::function<Disparity*(ftl::Configurable *, const std::string &)> f) { - if (!algorithms__) algorithms__ = new std::map<std::string, std::function<Disparity*(ftl::Configurable *, const std::string &)>>; - //LOG(INFO) << "Register disparity algorithm: " << n; - (*algorithms__)[n] = f; -} - -void Disparity::scaleInput( const cv::cuda::GpuMat& left_in, - const cv::cuda::GpuMat& right_in, - cv::cuda::GpuMat& left_out, - cv::cuda::GpuMat& right_out, - cv::cuda::Stream &stream) -{ - cv::cuda::resize(left_in, left_scaled_, size_, 0.0, 0.0, cv::INTER_CUBIC, stream); - left_out = left_scaled_; - cv::cuda::resize(right_in, right_scaled_, size_, 0.0, 0.0, cv::INTER_CUBIC, stream); - right_out = right_scaled_; -} - -void Disparity::scaleDisparity( const cv::Size& new_size, - cv::cuda::GpuMat& in, - cv::cuda::GpuMat& out, - cv::cuda::Stream& stream) -{ - cv::cuda::multiply(in, (double) new_size.width / (double) in.cols, in); - cv::cuda::resize(in, dispt_scaled_, new_size, 0.0, 0.0, cv::INTER_NEAREST, stream); - out = dispt_scaled_; -} - -// TODO:(Nick) Add remaining algorithms -/* -#include "algorithms/rtcensus.hpp" -static ftl::rgbd::detail::Disparity::Register rtcensus("rtcensus", ftl::algorithms::RTCensus::create); -*/ - -#ifdef HAVE_LIBSGM -#include "algorithms/fixstars_sgm.hpp" -static ftl::rgbd::detail::Disparity::Register fixstarssgm("libsgm", ftl::algorithms::FixstarsSGM::create); -#endif // HAVE_LIBSGM - diff --git a/components/rgbd-sources/src/disparity.hpp b/components/rgbd-sources/src/disparity.hpp deleted file mode 100644 index 2152378c1..000000000 --- a/components/rgbd-sources/src/disparity.hpp +++ /dev/null @@ -1,95 +0,0 @@ -/* - * Copyright 2019 Nicolas Pope - */ - -#ifndef _FTL_DISPARITY_HPP_ -#define _FTL_DISPARITY_HPP_ - -#include <opencv2/core.hpp> -#include <ftl/configurable.hpp> -#include <ftl/rgbd/frame.hpp> - -namespace ftl { -namespace rgbd { -namespace detail { - -/** - * Virtual base class for disparity algorithms. An automatic factory is used - * to construct instances of specific algorithms that implement this - * interface, for this to work a static instance of the Register class must - * be created in the algorithms cpp file. - */ -class Disparity : public ftl::Configurable { - public: - explicit Disparity(nlohmann::json &config); - - virtual void setMinDisparity(size_t min) { min_disp_ = min; } - virtual void setMaxDisparity(size_t max) { max_disp_ = max; } - - virtual void setMask(cv::Mat &mask) { mask_l_ = cv::cuda::GpuMat(mask); } - virtual void setMask(cv::cuda::GpuMat &mask) { mask_l_ = mask; } - - void scaleInput(const cv::cuda::GpuMat& left_in, - const cv::cuda::GpuMat& right_in, - cv::cuda::GpuMat& left_out, - cv::cuda::GpuMat& right_out, - cv::cuda::Stream &stream); - - void scaleDisparity(const cv::Size &new_size, - cv::cuda::GpuMat& in, - cv::cuda::GpuMat& out, - cv::cuda::Stream &stream); - - /** - * Pure virtual function representing the actual computation of - * disparity from left and right images to be implemented. - */ - virtual void compute(Frame &frame, cv::cuda::Stream &stream)=0; - virtual void compute(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &disp, cv::cuda::Stream &stream) - { - // FIXME: What were these for? - //ftl::rgbd::Frame frame; - //frame.create<cv::cuda::GpuMat>(ftl::codecs::Channel::Left) = l; - //frame.create<cv::cuda::GpuMat>(ftl::codecs::Channel::Right) = r; - //frame.create<cv::cuda::GpuMat>(ftl::codecs::Channel::Disparity) = disp; - } - - /** - * Factory registration class. - */ - class Register { - public: - // cppcheck-suppress * - Register(const std::string &n, std::function<Disparity*(ftl::Configurable *, const std::string &)> f) { - Disparity::_register(n,f); - }; - }; - - /** - * Factory instance creator where config contains an "algorithm" property - * used as the instance name to construct. - */ - static Disparity *create(ftl::Configurable *, const std::string &); - - protected: - static void _register(const std::string &n, std::function<Disparity*(ftl::Configurable *, const std::string &)> f); - -protected: - int min_disp_; - int max_disp_; - cv::Size size_; - - cv::cuda::GpuMat left_scaled_; - cv::cuda::GpuMat right_scaled_; - cv::cuda::GpuMat dispt_scaled_; - cv::cuda::GpuMat mask_l_; - - private: - static std::map<std::string,std::function<Disparity*(ftl::Configurable *, const std::string &)>> *algorithms__; -}; - -} -} -} - -#endif // _FTL_DISPARITY_HPP_ diff --git a/components/rgbd-sources/src/group.cpp b/components/rgbd-sources/src/group.cpp index 70c8402fc..55fd3c411 100644 --- a/components/rgbd-sources/src/group.cpp +++ b/components/rgbd-sources/src/group.cpp @@ -20,8 +20,11 @@ using ftl::codecs::Channels; Group::Group() : pipeline_(nullptr) { jobs_ = 0; + cjobs_ = 0; skip_ = false; name_ = "NoName"; + + builder_.setBufferSize(0); } Group::~Group() { @@ -74,15 +77,15 @@ void Group::_retrieveJob(ftl::rgbd::Source *src) { } } -void Group::_computeJob(ftl::rgbd::Source *src) { +void Group::_dispatchJob(ftl::rgbd::Source *src, int64_t ts) { try { - src->compute(); + src->dispatch(ts); } catch (std::exception &ex) { - LOG(ERROR) << "Exception when computing frame"; + LOG(ERROR) << "Exception when dispatching frame"; LOG(ERROR) << ex.what(); } catch (...) { - LOG(ERROR) << "Unknown exception when computing frame"; + LOG(ERROR) << "Unknown exception when dispatching frame"; } } @@ -94,10 +97,6 @@ int Group::streamID(const ftl::rgbd::Source *s) const { } void Group::onFrameSet(const ftl::rgbd::VideoCallback &cb) { - //if (latency_ == 0) { - // callback_ = cb; - //} - // 1. Capture camera frames with high precision cap_id_ = ftl::timer::add(ftl::timer::kTimerHighPrecision, [this](int64_t ts) { skip_ = jobs_ != 0; // Last frame not finished so skip all steps @@ -105,41 +104,26 @@ void Group::onFrameSet(const ftl::rgbd::VideoCallback &cb) { if (skip_) return true; for (auto s : sources_) { - s->capture(ts); + skip_ &= s->capture(ts); } return true; }); - // 2. After capture, swap any internal source double buffers - swap_id_ = ftl::timer::add(ftl::timer::kTimerSwap, [this](int64_t ts) { - if (skip_) return true; - for (auto s : sources_) { - s->swap(); - } - return true; - }); - - // 3. Issue IO retrieve ad compute jobs before finding a valid + // 2. Issue IO retrieve ad compute jobs before finding a valid // frame at required latency to pass to callback. main_id_ = ftl::timer::add(ftl::timer::kTimerMain, [this,cb](int64_t ts) { - //if (skip_) LOG(ERROR) << "SKIPPING TIMER JOB " << ts; if (skip_) return true; - //jobs_++; for (auto s : sources_) { - jobs_ += 2; + jobs_++; - ftl::pool.push([this,s](int id) { + //ftl::pool.push([this,s,ts](int id) { _retrieveJob(s); - //if (jobs_ == 0) LOG(INFO) << "LAST JOB = Retrieve"; + //LOG(INFO) << "Retrieve latency: " << ftl::timer::get_time()-ts; --jobs_; - }); - ftl::pool.push([this,s](int id) { - _computeJob(s); - //if (jobs_ == 0) LOG(INFO) << "LAST JOB = Compute"; - --jobs_; - }); + _dispatchJob(s, ts); + //}); } return true; }); @@ -150,18 +134,6 @@ void Group::onFrameSet(const ftl::rgbd::VideoCallback &cb) { }); } -void Group::addRawCallback(const std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> &f) { - for (auto s : sources_) { - s->addRawCallback(f); - } -} - -/*void Group::removeRawCallback(const std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> &f) { - for (auto s : sources_) { - s->removeRawCallback(f); - } -}*/ - void Group::setName(const std::string &name) { name_ = name; builder_.setName(name); diff --git a/components/rgbd-sources/src/source.cpp b/components/rgbd-sources/src/source.cpp index d39ea51d5..2a9af5889 100644 --- a/components/rgbd-sources/src/source.cpp +++ b/components/rgbd-sources/src/source.cpp @@ -1,5 +1,6 @@ #include <loguru.hpp> #include <ftl/rgbd/source.hpp> +#include "basesource.hpp" #include <ftl/threads.hpp> //#include "sources/net/net.hpp" @@ -8,11 +9,6 @@ #include "sources/middlebury/middlebury_source.hpp" #include "sources/screencapture/screencapture.hpp" -#ifdef HAVE_LIBARCHIVE -#include <ftl/rgbd/snapshot.hpp> -#include "sources/snapshot/snapshot_source.hpp" -#endif - //#include "sources/ftlfile/file_source.hpp" #ifdef HAVE_REALSENSE @@ -34,15 +30,15 @@ using ftl::rgbd::capability_t; using ftl::codecs::Channel; //using ftl::rgbd::detail::FileSource; using ftl::rgbd::Camera; -using ftl::rgbd::RawCallback; using ftl::rgbd::FrameCallback; -std::map<std::string, ftl::rgbd::Player*> Source::readers__; Source::Source(ftl::config::json_t &cfg) : Configurable(cfg), pose_(Eigen::Matrix4d::Identity()), net_(nullptr) { impl_ = nullptr; //params_ = {}; stream_ = 0; + is_dispatching = false; + is_retrieving = false; reset(); on("uri", [this](const ftl::config::Event &e) { @@ -55,6 +51,8 @@ Source::Source(ftl::config::json_t &cfg, ftl::net::Universe *net) : Configurable impl_ = nullptr; //params_ = {}; stream_ = 0; + is_dispatching = false; + is_retrieving = false; reset(); on("uri", [this](const ftl::config::Event &e) { @@ -67,36 +65,21 @@ Source::~Source() { if (impl_) delete impl_; } -cv::Mat Source::cameraMatrix() const { - cv::Mat m = (cv::Mat_<float>(3,3) << parameters().fx, 0.0, -parameters().cx, 0.0, parameters().fy, -parameters().cy, 0.0, 0.0, 1.0); - return m; -} +bool Source::isReady() { return (impl_) ? impl_->isReady() : false; } -ftl::rgbd::detail::Source *Source::_createImplementation() { - auto uristr = get<string>("uri"); - if (!uristr) { - //LOG(WARNING) << "Missing URI for source"; - return nullptr; - } - - ftl::URI uri(*uristr); - if (!uri.isValid()) { - LOG(WARNING) << "Invalid URI for source: " << *uristr; - return nullptr; - } +const Camera &Source::parameters() const { + if (impl_) return impl_->params_; + else throw FTL_Error("Cannot get parameters for bad source"); +} - switch (uri.getScheme()) { - case ftl::URI::SCHEME_FILE : return _createFileImpl(uri); - case ftl::URI::SCHEME_FTL : return _createNetImpl(uri); - case ftl::URI::SCHEME_DEVICE : return _createDeviceImpl(uri); - default: break; - } +ftl::rgbd::FrameState &Source::state() { return impl_->state_; } - LOG(WARNING) << "Unrecognised source URI: " << *uristr; - return nullptr; +cv::Mat Source::cameraMatrix() const { + cv::Mat m = (cv::Mat_<float>(3,3) << parameters().fx, 0.0, -parameters().cx, 0.0, parameters().fy, -parameters().cy, 0.0, 0.0, 1.0); + return m; } -ftl::rgbd::detail::Source *Source::_createFileImpl(const ftl::URI &uri) { +static ftl::rgbd::BaseSourceImpl *createFileImpl(const ftl::URI &uri, Source *host) { std::string path = uri.getPath(); // Note: This is non standard if (uri.getHost() == "." || uri.getHost() == "~") path = uri.getHost()+path; @@ -107,7 +90,7 @@ ftl::rgbd::detail::Source *Source::_createFileImpl(const ftl::URI &uri) { // Might be a directory if (ftl::is_directory(path)) { if (ftl::is_file(path + "/video.mp4")) { - return new StereoVideoSource(this, path); + return new StereoVideoSource(host, path); // } else if (ftl::is_file(path + "/im0.png")) { // return new MiddleburySource(this, path); } else { @@ -126,18 +109,9 @@ ftl::rgbd::detail::Source *Source::_createFileImpl(const ftl::URI &uri) { LOG(FATAL) << "File sources not supported"; return nullptr; } else if (ext == "png" || ext == "jpg") { - return new ImageSource(this, path); + return new ImageSource(host, path); } else if (ext == "mp4") { - return new StereoVideoSource(this, path); - } else if (ext == "tar" || ext == "gz") { -#ifdef HAVE_LIBARCHIVE - ftl::rgbd::SnapshotReader reader(path); - auto snapshot = reader.readArchive(); - return new ftl::rgbd::detail::SnapshotSource(this, snapshot, value("index", std::string("0"))); // TODO: Use URI fragment -#else - LOG(ERROR) << "Cannot read snapshots, libarchive not installed"; - return nullptr; -#endif // HAVE_LIBARCHIVE + return new StereoVideoSource(host, path); } else { LOG(WARNING) << "Unrecognised file type: " << path; } @@ -148,73 +122,43 @@ ftl::rgbd::detail::Source *Source::_createFileImpl(const ftl::URI &uri) { return nullptr; } -/*ftl::rgbd::Player *Source::__createReader(const std::string &path) { - if (readers__.find(path) != readers__.end()) { - return readers__[path]; - } - - std::ifstream *file = new std::ifstream; - file->open(path); - - // FIXME: This is a memory leak, must delete ifstream somewhere. - - auto *r = new ftl::rgbd::Player(*file); - readers__[path] = r; - r->begin(); - return r; -}*/ - -ftl::rgbd::detail::Source *Source::_createNetImpl(const ftl::URI &uri) { - LOG(FATAL) << "Net sources no longer supported"; - //return new NetSource(this); - return nullptr; -} - -ftl::rgbd::detail::Source *Source::_createDeviceImpl(const ftl::URI &uri) { - if (uri.getPathSegment(0) == "video") { - return new StereoVideoSource(this); +static ftl::rgbd::BaseSourceImpl *createDeviceImpl(const ftl::URI &uri, Source *host) { + if (uri.getPathSegment(0) == "video" || uri.getPathSegment(0) == "camera" || uri.getPathSegment(0) == "pylon") { + return new StereoVideoSource(host); } else if (uri.getPathSegment(0) == "realsense") { #ifdef HAVE_REALSENSE - return new RealsenseSource(this); + return new RealsenseSource(host); #else LOG(ERROR) << "You do not have 'librealsense2' installed"; #endif } else if (uri.getPathSegment(0) == "screen") { - return new ScreenCapture(this); - } else { - /*params_.width = value("width", 1280); - params_.height = value("height", 720); - params_.fx = value("focal", 700.0f); - params_.fy = params_.fx; - params_.cx = -(double)params_.width / 2.0; - params_.cy = -(double)params_.height / 2.0; - params_.minDepth = value("minDepth", 0.1f); - params_.maxDepth = value("maxDepth", 20.0f); - params_.doffs = 0; - params_.baseline = value("baseline", 0.0f);*/ + return new ScreenCapture(host); } return nullptr; } -void Source::getFrames(cv::Mat &rgb, cv::Mat &depth) { - if (bool(callback_)) LOG(WARNING) << "Cannot use getFrames and callback in source"; - SHARED_LOCK(mutex_,lk); - //rgb_.copyTo(rgb); - //depth_.copyTo(depth); - //rgb = rgb_; - //depth = depth_; -} +static ftl::rgbd::BaseSourceImpl *createImplementation(const std::string &uristr, Source *host) { + ftl::URI uri(uristr); + if (!uri.isValid()) { + LOG(WARNING) << "Invalid URI for source: " << uristr; + return nullptr; + } + switch (uri.getScheme()) { + case ftl::URI::SCHEME_FILE : return createFileImpl(uri, host); + case ftl::URI::SCHEME_DEVICE : return createDeviceImpl(uri, host); + default: break; + } + + LOG(WARNING) << "Unrecognised source URI: " << uristr; + return nullptr; +} void Source::setPose(const Eigen::Matrix4d &pose) { pose_ = pose; if (impl_) impl_->setPose(pose); } -const Eigen::Matrix4d &Source::getPose() const { - return pose_; -} - bool Source::hasCapabilities(capability_t c) { return (getCapabilities() & c) == c; } @@ -228,7 +172,11 @@ void Source::reset() { UNIQUE_LOCK(mutex_,lk); channel_ = Channel::None; if (impl_) delete impl_; - impl_ = _createImplementation(); + impl_ = nullptr; + + auto uristr = get<string>("uri"); + if (!uristr) return; + impl_ = createImplementation(*uristr, this); } bool Source::capture(int64_t ts) { @@ -238,13 +186,32 @@ bool Source::capture(int64_t ts) { } bool Source::retrieve() { - if (impl_) return impl_->retrieve(); - else return true; + is_retrieving = true; + bool status = false; + if (impl_) status = impl_->retrieve(frames_[0]); + is_retrieving = false; + return status; +} + +bool Source::dispatch(int64_t ts) { + if (!callback_) return false; + if (is_dispatching || is_retrieving) { + LOG(WARNING) << "Previous distance not completed"; + return false; + } + is_dispatching = true; + _swap(); + ftl::pool.push([this,ts](int id) { + callback_(ts, frames_[1]); + is_dispatching = false; + }); + return true; } -bool Source::compute(int N, int B) { - UNIQUE_LOCK(mutex_,lk); - return impl_ && impl_->compute(N,B); +void Source::_swap() { + auto tmp = std::move(frames_[0]); + frames_[0] = std::move(frames_[1]); + frames_[1] = std::move(tmp); } bool Source::setChannel(ftl::codecs::Channel c) { @@ -262,75 +229,4 @@ void Source::setCallback(const FrameCallback &cb) { callback_ = cb; } -void Source::addRawCallback(const RawCallback &f) { - UNIQUE_LOCK(mutex_,lk); - rawcallbacks_.push_back(f); -} - -void Source::removeRawCallback(const std::function<void(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt)> &f) { - UNIQUE_LOCK(mutex_,lk); - for (auto i=rawcallbacks_.begin(); i!=rawcallbacks_.end(); ++i) { - const auto targ = (*i).target<void(*)(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &, const ftl::codecs::Packet &)>(); - if (targ && targ == f.target<void(*)(ftl::rgbd::Source*, const ftl::codecs::StreamPacket &, const ftl::codecs::Packet &)>()) { - rawcallbacks_.erase(i); - LOG(INFO) << "Removing RAW callback"; - return; - } - } -} - -void Source::notifyRaw(const ftl::codecs::StreamPacket &spkt, const ftl::codecs::Packet &pkt) { - SHARED_LOCK(mutex_,lk); - for (auto &i : rawcallbacks_) { - i(this, spkt, pkt); - } -} - -/* - * Scale camera parameters to match resolution. - */ -Camera Camera::scaled(int width, int height) const { - const auto &cam = *this; - float scaleX = (float)width / (float)cam.width; - float scaleY = (float)height / (float)cam.height; - - //CHECK( abs(scaleX - scaleY) < 0.00000001f ); - - Camera newcam = cam; - newcam.width = width; - newcam.height = height; - newcam.fx *= scaleX; - newcam.fy *= scaleY; - newcam.cx *= scaleX; - newcam.cy *= scaleY; - newcam.doffs *= scaleX; - - return newcam; -} - -void Source::notify(int64_t ts, ftl::rgbd::Frame &f) { - //if (impl_) f.setOrigin(&impl_->state_); - if (callback_) callback_(ts, f); -} - -void Source::inject(const Eigen::Matrix4d &pose) { - ftl::codecs::StreamPacket spkt; - ftl::codecs::Packet pkt; - - spkt.timestamp = impl_->timestamp_; - spkt.frame_number = 0; - spkt.channel = Channel::Pose; - spkt.streamID = 0; - pkt.codec = ftl::codecs::codec_t::MSGPACK; - //pkt.definition = ftl::codecs::definition_t::Any; - pkt.bitrate = 0; - pkt.frame_count = 1; - pkt.flags = 0; - - std::vector<double> data(pose.data(), pose.data() + 4*4*sizeof(double)); - VectorBuffer buf(pkt.data); - msgpack::pack(buf, data); - - notifyRaw(spkt, pkt); -} diff --git a/components/rgbd-sources/src/sources/image/image.hpp b/components/rgbd-sources/src/sources/image/image.hpp index 2e2391b7c..9bf4f4f69 100644 --- a/components/rgbd-sources/src/sources/image/image.hpp +++ b/components/rgbd-sources/src/sources/image/image.hpp @@ -1,22 +1,23 @@ #ifndef _FTL_RGBD_IMAGE_HPP_ #define _FTL_RGBD_IMAGE_HPP_ +#include "../../basesource.hpp" + namespace ftl { namespace rgbd { namespace detail { -class ImageSource : public ftl::rgbd::detail::Source { +class ImageSource : public ftl::rgbd::BaseSourceImpl { public: - explicit ImageSource(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit ImageSource(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { } - ImageSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::detail::Source(host) { + ImageSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::BaseSourceImpl(host) { } - bool capture(int64_t ts) { timestamp_ = ts; return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return false; }; + bool capture(int64_t ts) { return true; } + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return false; }; }; diff --git a/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp b/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp index 229895049..656310c26 100644 --- a/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp +++ b/components/rgbd-sources/src/sources/middlebury/middlebury_source.cpp @@ -10,7 +10,7 @@ using ftl::rgbd::detail::Disparity; using std::string; MiddleburySource::MiddleburySource(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host), ready_(false) { + : ftl::rgbd::BaseSourceImpl(host), ready_(false) { // Not VALID } @@ -62,7 +62,7 @@ static bool loadMiddleburyCalib(const std::string &filename, ftl::rgbd::Camera & } MiddleburySource::MiddleburySource(ftl::rgbd::Source *host, const string &dir) - : ftl::rgbd::detail::Source(host), ready_(false) { + : ftl::rgbd::BaseSourceImpl(host), ready_(false) { double scaling = host->value("scaling", 0.5); @@ -159,8 +159,4 @@ void MiddleburySource::_performDisparity() { //disparityToDepthTRUE(depth_, depth_, params_); } -bool MiddleburySource::compute(int n, int b) { - //_performDisparity(); - return true; -} diff --git a/components/rgbd-sources/src/sources/middlebury/middlebury_source.hpp b/components/rgbd-sources/src/sources/middlebury/middlebury_source.hpp index d273d23a6..d102dbeba 100644 --- a/components/rgbd-sources/src/sources/middlebury/middlebury_source.hpp +++ b/components/rgbd-sources/src/sources/middlebury/middlebury_source.hpp @@ -4,7 +4,7 @@ #include <loguru.hpp> -#include <ftl/rgbd/source.hpp> +#include "../../basesource.hpp" #include <ftl/cuda_common.hpp> namespace ftl { @@ -13,15 +13,14 @@ namespace detail { class Disparity; -class MiddleburySource : public detail::Source { +class MiddleburySource : public BaseSourceImpl { public: explicit MiddleburySource(ftl::rgbd::Source *); MiddleburySource(ftl::rgbd::Source *, const std::string &dir); ~MiddleburySource() {}; - bool capture(int64_t ts) { timestamp_ = ts; return true; } - bool retrieve() { return true; } - bool compute(int n, int b); + bool capture(int64_t ts) { return true; } + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return ready_; } private: diff --git a/components/rgbd-sources/src/sources/realsense/realsense_source.cpp b/components/rgbd-sources/src/sources/realsense/realsense_source.cpp index ea061ba2c..57e212027 100644 --- a/components/rgbd-sources/src/sources/realsense/realsense_source.cpp +++ b/components/rgbd-sources/src/sources/realsense/realsense_source.cpp @@ -9,7 +9,7 @@ using ftl::codecs::Channel; using cv::cuda::GpuMat; RealsenseSource::RealsenseSource(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host), align_to_depth_(RS2_STREAM_COLOR) { + : ftl::rgbd::BaseSourceImpl(host), align_to_depth_(RS2_STREAM_COLOR) { capabilities_ = kCapVideo; rs2::config cfg; @@ -45,9 +45,9 @@ RealsenseSource::~RealsenseSource() { } -bool RealsenseSource::compute(int n, int b) { - frame_.reset(); - frame_.setOrigin(&state_); +bool RealsenseSource::retrieve(ftl::rgbd::Frame &frame) { + frame.reset(); + frame.setOrigin(&state_); rs2::frameset frames; if (!pipe_.poll_for_frames(&frames)) return false; //wait_for_frames(); @@ -66,7 +66,7 @@ bool RealsenseSource::compute(int n, int b) { } cv::Mat tmp_rgb(cv::Size(w, h), CV_8UC4, (void*)cframe.get_data(), cv::Mat::AUTO_STEP); - frame_.create<GpuMat>(Channel::Colour).upload(tmp_rgb); + frame.create<GpuMat>(Channel::Colour).upload(tmp_rgb); } else { frames = align_to_depth_.process(frames); @@ -77,13 +77,12 @@ bool RealsenseSource::compute(int n, int b) { cv::Mat tmp_depth(cv::Size((int)w, (int)h), CV_16UC1, (void*)depth.get_data(), depth.get_stride_in_bytes()); tmp_depth.convertTo(tmp_depth, CV_32FC1, scale_); - frame_.create<GpuMat>(Channel::Depth).upload(tmp_depth); + frame.create<GpuMat>(Channel::Depth).upload(tmp_depth); cv::Mat tmp_rgb(cv::Size(w, h), CV_8UC4, (void*)rscolour_.get_data(), cv::Mat::AUTO_STEP); - frame_.create<GpuMat>(Channel::Colour).upload(tmp_rgb); + frame.create<GpuMat>(Channel::Colour).upload(tmp_rgb); } - host_->notify(timestamp_, frame_); - return true; + return true; } bool RealsenseSource::isReady() { diff --git a/components/rgbd-sources/src/sources/realsense/realsense_source.hpp b/components/rgbd-sources/src/sources/realsense/realsense_source.hpp index 371d305b7..83274aecc 100644 --- a/components/rgbd-sources/src/sources/realsense/realsense_source.hpp +++ b/components/rgbd-sources/src/sources/realsense/realsense_source.hpp @@ -2,7 +2,7 @@ #ifndef _FTL_RGBD_REALSENSE_HPP_ #define _FTL_RGBD_REALSENSE_HPP_ -#include <ftl/rgbd/detail/source.hpp> +#include "../../basesource.hpp" #include <librealsense2/rs.hpp> #include <string> @@ -12,14 +12,13 @@ namespace rgbd { namespace detail { -class RealsenseSource : public ftl::rgbd::detail::Source { +class RealsenseSource : public ftl::rgbd::BaseSourceImpl { public: explicit RealsenseSource(ftl::rgbd::Source *host); ~RealsenseSource(); - bool capture(int64_t ts) { timestamp_ = ts; return true; } - bool retrieve() { return true; } - bool compute(int n=-1, int b=-1); + bool capture(int64_t ts) { return true; } + bool retrieve(ftl::rgbd::Frame &frame); bool isReady(); private: diff --git a/components/rgbd-sources/src/sources/screencapture/screencapture.cpp b/components/rgbd-sources/src/sources/screencapture/screencapture.cpp index 5a6af978f..39ec56c09 100644 --- a/components/rgbd-sources/src/sources/screencapture/screencapture.cpp +++ b/components/rgbd-sources/src/sources/screencapture/screencapture.cpp @@ -55,7 +55,7 @@ static Eigen::Matrix4d matrix(const cv::Vec3d &rvec, const cv::Vec3d &tvec) { ScreenCapture::ScreenCapture(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host) { + : ftl::rgbd::BaseSourceImpl(host) { capabilities_ = kCapVideo; ready_ = false; @@ -190,14 +190,7 @@ ScreenCapture::~ScreenCapture() { #endif } -void ScreenCapture::swap() { -} - -bool ScreenCapture::retrieve() { - return true; -} - -bool ScreenCapture::compute(int n, int b) { +bool ScreenCapture::retrieve(ftl::rgbd::Frame &frame) { if (!ready_) return false; cv::Mat img; @@ -206,15 +199,14 @@ bool ScreenCapture::compute(int n, int b) { img = cv::Mat(params_.height, params_.width, CV_8UC4, impl_state_->ximg->data); #endif - frame_.reset(); - frame_.setOrigin(&state_); + frame.reset(); + frame.setOrigin(&state_); if (!img.empty()) { - frame_.create<cv::Mat>(Channel::Colour) = img; + frame.create<cv::Mat>(Channel::Colour) = img; } - host_->notify(timestamp_, frame_); - return true; + return true; } bool ScreenCapture::isReady() { diff --git a/components/rgbd-sources/src/sources/screencapture/screencapture.hpp b/components/rgbd-sources/src/sources/screencapture/screencapture.hpp index 8480359e6..163ab106c 100644 --- a/components/rgbd-sources/src/sources/screencapture/screencapture.hpp +++ b/components/rgbd-sources/src/sources/screencapture/screencapture.hpp @@ -1,7 +1,7 @@ #ifndef _FTL_RGBD_SCREENCAPTURE_HPP_ #define _FTL_RGBD_SCREENCAPTURE_HPP_ -#include <ftl/rgbd/detail/source.hpp> +#include "../../basesource.hpp" #include <ftl/config.h> namespace ftl { @@ -17,16 +17,14 @@ typedef X11State ImplState; typedef int ImplState; #endif -class ScreenCapture : public ftl::rgbd::detail::Source { +class ScreenCapture : public ftl::rgbd::BaseSourceImpl { public: explicit ScreenCapture(ftl::rgbd::Source *host); ~ScreenCapture(); - bool capture(int64_t ts) { timestamp_ = ts; return true; }; - void swap() override; - bool retrieve(); - bool compute(int n=-1, int b=-1); - bool isReady(); + bool capture(int64_t ts) override { return true; }; + bool retrieve(ftl::rgbd::Frame &frame) override; + bool isReady() override; size_t getOffsetX() const { return (offset_x_ > full_width_-params_.width) ? full_width_-params_.width : offset_x_; } size_t getOffsetY() const { return (offset_y_ > full_height_-params_.height) ? full_height_-params_.height : offset_y_; } diff --git a/components/rgbd-sources/src/sources/snapshot/snapshot_source.cpp b/components/rgbd-sources/src/sources/snapshot/snapshot_source.cpp index 95d8b9e07..2179b2719 100644 --- a/components/rgbd-sources/src/sources/snapshot/snapshot_source.cpp +++ b/components/rgbd-sources/src/sources/snapshot/snapshot_source.cpp @@ -15,7 +15,7 @@ using ftl::codecs::Channel; using std::string; using std::vector; -SnapshotSource::SnapshotSource(ftl::rgbd::Source *host, Snapshot &snapshot, const string &id) : detail::Source(host) { +SnapshotSource::SnapshotSource(ftl::rgbd::Source *host, Snapshot &snapshot, const string &id) : BaseSourceImpl(host) { snapshot_ = snapshot; camera_idx_ = std::atoi(id.c_str()); frame_idx_ = 0; diff --git a/components/rgbd-sources/src/sources/snapshot/snapshot_source.hpp b/components/rgbd-sources/src/sources/snapshot/snapshot_source.hpp index 80a0bf392..a6149dec3 100644 --- a/components/rgbd-sources/src/sources/snapshot/snapshot_source.hpp +++ b/components/rgbd-sources/src/sources/snapshot/snapshot_source.hpp @@ -11,7 +11,7 @@ namespace ftl { namespace rgbd { namespace detail { -class SnapshotSource : public detail::Source { +class SnapshotSource : public BaseSourceImpl { public: explicit SnapshotSource(ftl::rgbd::Source *); SnapshotSource(ftl::rgbd::Source *, ftl::rgbd::Snapshot &snapshot, const std::string &id); diff --git a/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp b/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp index 523608a04..3eaa1bc2d 100644 --- a/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/calibrate.hpp @@ -7,7 +7,6 @@ #include <opencv2/core.hpp> #include <opencv2/core/cuda.hpp> -#include "local.hpp" #include <string> #include <vector> #include <ftl/rgbd/camera.hpp> diff --git a/components/rgbd-sources/src/sources/stereovideo/device.hpp b/components/rgbd-sources/src/sources/stereovideo/device.hpp new file mode 100644 index 000000000..7a7fcb45b --- /dev/null +++ b/components/rgbd-sources/src/sources/stereovideo/device.hpp @@ -0,0 +1,55 @@ +#ifndef _FTL_RGBD_STEREOVIDEO_DEVICE_HPP_ +#define _FTL_RGBD_STEREOVIDEO_DEVICE_HPP_ + +#include <ftl/configurable.hpp> +#include <ftl/cuda_common.hpp> +#include <string> + +namespace ftl { +namespace rgbd { +namespace detail { + +class Calibrate; + +struct DeviceDetails { + std::string name; + int id; + size_t maxwidth; + size_t maxheight; +}; + +/** + * Abstract base class for camera or stereo camera sources. Just wraps the + * basic grab and retrieve functionality with rectification. + * + * @see OpenCVDevice + * @see PylonDevice + */ +class Device : public Configurable { + public: + explicit Device(nlohmann::json &config); + virtual ~Device(); + + //virtual const std::vector<DeviceDetails> &listDevices()=0; + + virtual bool grab()=0; + virtual bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream)=0; + + virtual unsigned int width() const =0; + virtual unsigned int height() const =0; + + virtual unsigned int fullWidth() const =0; + virtual unsigned int fullHeight() const =0; + + inline bool hasHigherRes() const { return fullWidth() != width(); } + + virtual double getTimestamp() const =0; + + virtual bool isStereo() const =0; +}; + +} +} +} + +#endif \ No newline at end of file diff --git a/components/rgbd-sources/src/sources/stereovideo/local.cpp b/components/rgbd-sources/src/sources/stereovideo/opencv.cpp similarity index 94% rename from components/rgbd-sources/src/sources/stereovideo/local.cpp rename to components/rgbd-sources/src/sources/stereovideo/opencv.cpp index a6f401748..23c5165a8 100644 --- a/components/rgbd-sources/src/sources/stereovideo/local.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/opencv.cpp @@ -9,7 +9,7 @@ #include <ftl/threads.hpp> #include <ftl/profiler.hpp> -#include "local.hpp" +#include "opencv.hpp" #include "calibrate.hpp" #include <opencv2/core.hpp> #include <opencv2/opencv.hpp> @@ -30,7 +30,7 @@ #pragma comment(lib, "mfuuid.lib") #endif -using ftl::rgbd::detail::LocalSource; +using ftl::rgbd::detail::OpenCVDevice; using ftl::rgbd::detail::Calibrate; using cv::Mat; using cv::VideoCapture; @@ -42,8 +42,8 @@ using std::chrono::high_resolution_clock; using std::chrono::milliseconds; using std::this_thread::sleep_for; -LocalSource::LocalSource(nlohmann::json &config) - : Configurable(config), timestamp_(0.0) { +OpenCVDevice::OpenCVDevice(nlohmann::json &config) + : ftl::rgbd::detail::Device(config), timestamp_(0.0) { std::vector<ftl::rgbd::detail::DeviceDetails> devices = _selectDevices(); @@ -142,12 +142,11 @@ LocalSource::LocalSource(nlohmann::json &config) hres_hm_ = cv::cuda::HostMem(height_, width_, CV_8UC4); } -LocalSource::LocalSource(nlohmann::json &config, const string &vid) - : Configurable(config), timestamp_(0.0) { - LOG(FATAL) << "Stereo video file sources no longer supported"; +OpenCVDevice::~OpenCVDevice() { + } -std::vector<ftl::rgbd::detail::DeviceDetails> LocalSource::_selectDevices() { +std::vector<ftl::rgbd::detail::DeviceDetails> OpenCVDevice::_selectDevices() { std::vector<ftl::rgbd::detail::DeviceDetails> devices; #ifdef WIN32 @@ -295,7 +294,7 @@ std::vector<ftl::rgbd::detail::DeviceDetails> LocalSource::_selectDevices() { } -bool LocalSource::grab() { +bool OpenCVDevice::grab() { if (!camera_a_) return false; if (camera_b_) { @@ -312,7 +311,7 @@ bool LocalSource::grab() { return true; } -bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, +bool OpenCVDevice::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda::GpuMat &l_hres_out, cv::Mat &r_hres_out, Calibrate *c, cv::cuda::Stream &stream) { Mat l, r ,hres; @@ -410,11 +409,11 @@ bool LocalSource::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, return true; } -double LocalSource::getTimestamp() const { +double OpenCVDevice::getTimestamp() const { return timestamp_; } -bool LocalSource::isStereo() const { +bool OpenCVDevice::isStereo() const { return stereo_ && !nostereo_; } diff --git a/components/rgbd-sources/src/sources/stereovideo/local.hpp b/components/rgbd-sources/src/sources/stereovideo/opencv.hpp similarity index 50% rename from components/rgbd-sources/src/sources/stereovideo/local.hpp rename to components/rgbd-sources/src/sources/stereovideo/opencv.hpp index 243df4c47..1db067b8d 100644 --- a/components/rgbd-sources/src/sources/stereovideo/local.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/opencv.hpp @@ -1,9 +1,7 @@ #ifndef _FTL_LOCAL_HPP_ #define _FTL_LOCAL_HPP_ -#include <ftl/configurable.hpp> -#include <ftl/cuda_common.hpp> -#include <string> +#include "device.hpp" namespace cv { class Mat; @@ -14,39 +12,25 @@ namespace ftl { namespace rgbd { namespace detail { -class Calibrate; - -struct DeviceDetails { - std::string name; - int id; - size_t maxwidth; - size_t maxheight; -}; - -class LocalSource : public Configurable { +class OpenCVDevice : public ftl::rgbd::detail::Device { public: - explicit LocalSource(nlohmann::json &config); - LocalSource(nlohmann::json &config, const std::string &vid); - - //bool left(cv::Mat &m); - //bool right(cv::Mat &m); - bool grab(); - bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream); + explicit OpenCVDevice(nlohmann::json &config); + ~OpenCVDevice(); - unsigned int width() const { return dwidth_; } - unsigned int height() const { return dheight_; } + static std::vector<DeviceDetails> listDevices(); + + bool grab() override; + bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream) override; - unsigned int fullWidth() const { return width_; } - unsigned int fullHeight() const { return height_; } + unsigned int width() const override { return dwidth_; } + unsigned int height() const override { return dheight_; } - inline bool hasHigherRes() const { return dwidth_ != width_; } - - //void setFramerate(float fps); - //float getFramerate() const; + unsigned int fullWidth() const override { return width_; } + unsigned int fullHeight() const override { return height_; } - double getTimestamp() const; + double getTimestamp() const override; - bool isStereo() const; + bool isStereo() const override; private: double timestamp_; diff --git a/components/rgbd-sources/src/sources/stereovideo/pylon.cpp b/components/rgbd-sources/src/sources/stereovideo/pylon.cpp new file mode 100644 index 000000000..b8155489e --- /dev/null +++ b/components/rgbd-sources/src/sources/stereovideo/pylon.cpp @@ -0,0 +1,250 @@ +#include "pylon.hpp" + +#include "calibrate.hpp" +#include <loguru.hpp> +#include <ftl/threads.hpp> +#include <ftl/rgbd/source.hpp> +#include <ftl/profiler.hpp> + +#include <pylon/PylonIncludes.h> +#include <pylon/BaslerUniversalInstantCamera.h> + +#include <opencv2/imgproc.hpp> + +using ftl::rgbd::detail::PylonDevice; +using std::string; +using ftl::codecs::Channel; +using cv::cuda::GpuMat; +using cv::Mat; +using namespace Pylon; + +PylonDevice::PylonDevice(nlohmann::json &config) + : ftl::rgbd::detail::Device(config), ready_(false), lcam_(nullptr), rcam_(nullptr) { + + auto &inst = CTlFactory::GetInstance(); + + Pylon::DeviceInfoList_t devices; + inst.EnumerateDevices(devices); + + if (devices.size() == 0) { + LOG(ERROR) << "No Pylon devices attached"; + return; + } else { + for (auto d : devices) { + LOG(INFO) << " - found Pylon device - " << d.GetFullName() << "(" << d.GetModelName() << ")"; + } + } + + try { + lcam_ = new CBaslerUniversalInstantCamera( CTlFactory::GetInstance().CreateDevice(devices[0])); + lcam_->RegisterConfiguration( new Pylon::CSoftwareTriggerConfiguration, Pylon::RegistrationMode_ReplaceAll, Pylon::Cleanup_Delete); + lcam_->Open(); + + if (devices.size() >= 2) { + rcam_ = new CBaslerUniversalInstantCamera( CTlFactory::GetInstance().CreateDevice(devices[1])); + rcam_->RegisterConfiguration( new Pylon::CSoftwareTriggerConfiguration, Pylon::RegistrationMode_ReplaceAll, Pylon::Cleanup_Delete); + rcam_->Open(); + } + + _configureCamera(lcam_); + if (rcam_) _configureCamera(rcam_); + + lcam_->StartGrabbing( Pylon::GrabStrategy_OneByOne); + if (rcam_) rcam_->StartGrabbing( Pylon::GrabStrategy_OneByOne); + + ready_ = true; + } catch (const Pylon::GenericException &e) { + // Error handling. + LOG(ERROR) << "Pylon: An exception occurred - " << e.GetDescription(); + } + + // Choose a good default depth res + width_ = value("depth_width", std::min(1280u,fullwidth_)) & 0xFFFe; + float aspect = float(fullheight_) / float(fullwidth_); + height_ = value("depth_height", std::min(uint32_t(aspect*float(width_)), fullheight_)) & 0xFFFe; + + LOG(INFO) << "Depth resolution: " << width_ << "x" << height_; + + // Allocate page locked host memory for fast GPU transfer + left_hm_ = cv::cuda::HostMem(height_, width_, CV_8UC4); + right_hm_ = cv::cuda::HostMem(height_, width_, CV_8UC4); + hres_hm_ = cv::cuda::HostMem(fullheight_, fullwidth_, CV_8UC4); +} + +PylonDevice::~PylonDevice() { + +} + +std::vector<ftl::rgbd::detail::DeviceDetails> PylonDevice::listDevices() { + auto &inst = CTlFactory::GetInstance(); + + Pylon::DeviceInfoList_t devices; + inst.EnumerateDevices(devices); + + std::vector<ftl::rgbd::detail::DeviceDetails> results; + + int count=0; + for (auto d : devices) { + //LOG(INFO) << " - found Pylon device - " << d.GetFullName() << "(" << d.GetModelName() << ")"; + auto &r = results.emplace_back(); + r.id = count++; + r.name = d.GetModelName(); + r.maxheight = 0; + r.maxwidth = 0; + } + + return results; +} + +void PylonDevice::_configureCamera(CBaslerUniversalInstantCamera *cam) { + // Get the camera control object. + GenApi::INodeMap& nodemap = cam->GetNodeMap(); + // Get the parameters for setting the image area of interest (Image AOI). + CIntegerParameter width(nodemap, "Width"); + CIntegerParameter height(nodemap, "Height"); + CIntegerParameter offsetX(nodemap, "OffsetX"); + CIntegerParameter offsetY(nodemap, "OffsetY"); + + fullwidth_ = width.GetValue(); + fullheight_ = height.GetValue(); + + LOG(INFO) << "Camera resolution = " << fullwidth_ << "x" << fullheight_; + + // Set the pixel data format. + CEnumParameter format(nodemap, "PixelFormat"); + LOG(INFO) << "Camera format: " << format.GetValue(); + + if (format.CanSetValue("BayerBG8")) { // YCbCr422_8 + format.SetValue("BayerBG8"); + } else { + LOG(WARNING) << "Could not change pixel format"; + } +} + +bool PylonDevice::grab() { + if (!isReady()) return false; + + //int dev; + //cudaGetDevice(&dev); + //LOG(INFO) << "Current cuda device = " << dev; + + try { + FTL_Profile("Frame Capture", 0.001); + if (rcam_) rcam_->WaitForFrameTriggerReady( 30, Pylon::TimeoutHandling_ThrowException); + else lcam_->WaitForFrameTriggerReady( 30, Pylon::TimeoutHandling_ThrowException); + + lcam_->ExecuteSoftwareTrigger(); + if (rcam_) rcam_->ExecuteSoftwareTrigger(); + } catch (const GenericException &e) { + LOG(ERROR) << "Pylon: Trigger exception - " << e.GetDescription(); + return false; + } + + return true; +} + +bool PylonDevice::get(cv::cuda::GpuMat &l_out, cv::cuda::GpuMat &r_out, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream) { + if (!isReady()) return false; + + Mat l, r ,hres; + + // Use page locked memory + l = left_hm_.createMatHeader(); + r = right_hm_.createMatHeader(); + hres = hres_hm_.createMatHeader(); + + Mat &lfull = (!hasHigherRes()) ? l : hres; + Mat &rfull = (!hasHigherRes()) ? r : rtmp_; + + //ftl::cuda::setDevice(); + + //int dev; + //cudaGetDevice(&dev); + //LOG(INFO) << "Current cuda device = " << dev; + + try { + FTL_Profile("Frame Retrieve", 0.005); + std::future<bool> future_b; + if (rcam_) { + future_b = std::move(ftl::pool.push([this,&rfull,&r,&l,c,&r_out,&h_r,&stream](int id) { + Pylon::CGrabResultPtr result_right; + int rcount = 0; + if (rcam_ && rcam_->RetrieveResult(0, result_right, Pylon::TimeoutHandling_Return)) ++rcount; + + if (rcount == 0 || !result_right->GrabSucceeded()) { + LOG(ERROR) << "Retrieve failed"; + return false; + } + + cv::Mat wrap_right( + result_right->GetHeight(), + result_right->GetWidth(), + CV_8UC1, + (uint8_t*)result_right->GetBuffer()); + + cv::cvtColor(wrap_right, rfull, cv::COLOR_BayerBG2BGRA); + + if (isStereo()) { + c->rectifyRight(rfull); + + if (hasHigherRes()) { + cv::resize(rfull, r, r.size(), 0.0, 0.0, cv::INTER_CUBIC); + h_r = rfull; + } + else { + h_r = Mat(); + } + } + + r_out.upload(r, stream); + return true; + })); + } + + Pylon::CGrabResultPtr result_left; + int lcount = 0; + { + if (lcam_->RetrieveResult(0, result_left, Pylon::TimeoutHandling_Return)) ++lcount; + } + + if (lcount == 0 || !result_left->GrabSucceeded()) { + LOG(ERROR) << "Retrieve failed"; + return false; + } + + cv::Mat wrap_left( + result_left->GetHeight(), + result_left->GetWidth(), + CV_8UC1, + (uint8_t*)result_left->GetBuffer()); + + cv::cvtColor(wrap_left, lfull, cv::COLOR_BayerBG2BGRA); + + if (isStereo()) { + c->rectifyLeft(lfull); + } + + if (hasHigherRes()) { + cv::resize(lfull, l, l.size(), 0.0, 0.0, cv::INTER_CUBIC); + h_l.upload(hres, stream); + } else { + h_l = cv::cuda::GpuMat(); + } + + l_out.upload(l, stream); + + if (rcam_) { + future_b.wait(); + } + + } catch (const GenericException &e) { + LOG(ERROR) << "Pylon: An exception occurred - " << e.GetDescription(); + } + + return true; +} + +bool PylonDevice::isReady() const { + return lcam_ && lcam_->IsOpen(); +} + diff --git a/components/rgbd-sources/src/sources/stereovideo/pylon.hpp b/components/rgbd-sources/src/sources/stereovideo/pylon.hpp new file mode 100644 index 000000000..84b0742fb --- /dev/null +++ b/components/rgbd-sources/src/sources/stereovideo/pylon.hpp @@ -0,0 +1,60 @@ +#pragma once +#ifndef _FTL_RGBD_PYLONDEVICE_HPP_ +#define _FTL_RGBD_PYLONDEVICE_HPP_ + +#include "device.hpp" +#include <string> + +namespace Pylon { +class CBaslerUniversalInstantCamera; +} + +namespace ftl { +namespace rgbd { +namespace detail { + +class PylonDevice : public ftl::rgbd::detail::Device { + public: + explicit PylonDevice(nlohmann::json &config); + ~PylonDevice(); + + static std::vector<DeviceDetails> listDevices(); + + bool grab() override; + bool get(cv::cuda::GpuMat &l, cv::cuda::GpuMat &r, cv::cuda::GpuMat &h_l, cv::Mat &h_r, Calibrate *c, cv::cuda::Stream &stream) override; + + unsigned int width() const override { return width_; } + unsigned int height() const override { return height_; }; + + unsigned int fullWidth() const override { return fullwidth_; } + unsigned int fullHeight() const override { return fullheight_; } + + double getTimestamp() const override { return 0.0; } + + bool isStereo() const override { return lcam_ && rcam_; } + + bool isReady() const; + + private: + bool ready_; + Pylon::CBaslerUniversalInstantCamera *lcam_; + Pylon::CBaslerUniversalInstantCamera *rcam_; + cv::Mat tmp_; + uint32_t fullwidth_; + uint32_t fullheight_; + uint32_t width_; + uint32_t height_; + + cv::cuda::HostMem left_hm_; + cv::cuda::HostMem right_hm_; + cv::cuda::HostMem hres_hm_; + cv::Mat rtmp_; + + void _configureCamera(Pylon::CBaslerUniversalInstantCamera *cam); +}; + +} +} +} + +#endif // _FTL_RGBD_PYLON_HPP_ diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp index dd4e2dc3e..21561726c 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.cpp @@ -24,22 +24,38 @@ #include "ftl/threads.hpp" #include "calibrate.hpp" -#include "local.hpp" -#include "disparity.hpp" +#include "opencv.hpp" + +#ifdef HAVE_PYLON +#include "pylon.hpp" +#endif using ftl::rgbd::detail::Calibrate; -using ftl::rgbd::detail::LocalSource; using ftl::rgbd::detail::StereoVideoSource; using ftl::codecs::Channel; using std::string; +ftl::rgbd::detail::Device::Device(nlohmann::json &config) : Configurable(config) { + +} + +ftl::rgbd::detail::Device::~Device() { + +} + StereoVideoSource::StereoVideoSource(ftl::rgbd::Source *host) - : ftl::rgbd::detail::Source(host), ready_(false) { - init(""); + : ftl::rgbd::BaseSourceImpl(host), ready_(false) { + auto uri = host->get<std::string>("uri"); + if (uri) { + init(*uri); + } else { + init(""); + } + } StereoVideoSource::StereoVideoSource(ftl::rgbd::Source *host, const string &file) - : ftl::rgbd::detail::Source(host), ready_(false) { + : ftl::rgbd::BaseSourceImpl(host), ready_(false) { init(file); } @@ -52,30 +68,43 @@ StereoVideoSource::~StereoVideoSource() { void StereoVideoSource::init(const string &file) { capabilities_ = kCapVideo | kCapStereo; - if (ftl::is_video(file)) { - // Load video file - LOG(INFO) << "Using video file..."; - lsrc_ = ftl::create<LocalSource>(host_, "feed", file); - } else if (ftl::is_directory(file)) { - // FIXME: This is not an ideal solution... - ftl::config::addPath(file); - - auto vid = ftl::locateFile("video.mp4"); - if (!vid) { - LOG(FATAL) << "No video.mp4 file found in provided paths (" << file << ")"; - } else { - LOG(INFO) << "Using test directory..."; - lsrc_ = ftl::create<LocalSource>(host_, "feed", *vid); + ftl::URI uri(file); + + if (uri.getScheme() == ftl::URI::SCHEME_DEVICE) { + if (uri.getPathSegment(0) == "pylon") { + #ifdef HAVE_PYLON + LOG(INFO) << "Using Pylon..."; + lsrc_ = ftl::create<ftl::rgbd::detail::PylonDevice>(host_, "feed"); + #else + throw FTL_Error("Not built with pylon support"); + #endif + } else if (uri.getPathSegment(0) == "opencv") { + // Use cameras + LOG(INFO) << "Using OpenCV cameras..."; + lsrc_ = ftl::create<ftl::rgbd::detail::OpenCVDevice>(host_, "feed"); + } else if (uri.getPathSegment(0) == "video" || uri.getPathSegment(0) == "camera") { + // Now detect automatically which device to use + #ifdef HAVE_PYLON + auto pylon_devices = ftl::rgbd::detail::PylonDevice::listDevices(); + if (pylon_devices.size() > 0) { + LOG(INFO) << "Using Pylon..."; + lsrc_ = ftl::create<ftl::rgbd::detail::PylonDevice>(host_, "feed"); + } else { + // Use cameras + LOG(INFO) << "Using OpenCV cameras..."; + lsrc_ = ftl::create<ftl::rgbd::detail::OpenCVDevice>(host_, "feed"); + } + #else + // Use cameras + LOG(INFO) << "Using OpenCV cameras..."; + lsrc_ = ftl::create<ftl::rgbd::detail::OpenCVDevice>(host_, "feed"); + #endif } } - else { - // Use cameras - LOG(INFO) << "Using cameras..."; - lsrc_ = ftl::create<LocalSource>(host_, "feed"); - } + + if (!lsrc_) return; // throw? color_size_ = cv::Size(lsrc_->width(), lsrc_->height()); - frames_ = std::vector<Frame>(2); pipeline_input_ = ftl::config::create<ftl::operators::Graph>(host_, "input"); #ifdef HAVE_OPTFLOW @@ -275,16 +304,13 @@ void StereoVideoSource::updateParameters() { } bool StereoVideoSource::capture(int64_t ts) { - capts_ = timestamp_; - timestamp_ = ts; lsrc_->grab(); return true; } -bool StereoVideoSource::retrieve() { +bool StereoVideoSource::retrieve(ftl::rgbd::Frame &frame) { FTL_Profile("Stereo Retrieve", 0.03); - auto &frame = frames_[0]; frame.reset(); frame.setOrigin(&state_); @@ -312,37 +338,6 @@ bool StereoVideoSource::retrieve() { return true; } -void StereoVideoSource::swap() { - auto tmp = std::move(frames_[0]); - frames_[0] = std::move(frames_[1]); - frames_[1] = std::move(tmp); -} - -bool StereoVideoSource::compute(int n, int b) { - auto &frame = frames_[1]; - - if (lsrc_->isStereo()) { - if (!frame.hasChannel(Channel::Left) || - !frame.hasChannel(Channel::Right)) { - - return false; - } - - cv::cuda::GpuMat& left = frame.get<cv::cuda::GpuMat>(Channel::Left); - cv::cuda::GpuMat& right = frame.get<cv::cuda::GpuMat>(Channel::Right); - - if (left.empty() || right.empty()) { return false; } - //stream_.waitForCompletion(); - - } - else { - if (!frame.hasChannel(Channel::Left)) { return false; } - } - - host_->notify(capts_, frame); - return true; -} - bool StereoVideoSource::isReady() { return ready_; } diff --git a/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp b/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp index 52ec6f393..2b6fc3a83 100644 --- a/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp +++ b/components/rgbd-sources/src/sources/stereovideo/stereovideo.hpp @@ -2,7 +2,7 @@ #ifndef _FTL_RGBD_STEREOVIDEO_HPP_ #define _FTL_RGBD_STEREOVIDEO_HPP_ -#include <ftl/rgbd/source.hpp> +#include "../../basesource.hpp" #include <ftl/operators/operator.hpp> #include <string> @@ -11,7 +11,7 @@ namespace ftl { namespace rgbd { namespace detail { -class LocalSource; +class Device; class Calibrate; class Disparity; @@ -19,24 +19,22 @@ class Disparity; * RGBD source from either a stereo video file with left + right images, or * direct from two camera devices. */ -class StereoVideoSource : public detail::Source { +class StereoVideoSource : public BaseSourceImpl { public: explicit StereoVideoSource(ftl::rgbd::Source*); StereoVideoSource(ftl::rgbd::Source*, const std::string &); ~StereoVideoSource(); - void swap(); - bool capture(int64_t ts); - bool retrieve(); - bool compute(int n, int b); - bool isReady(); + bool capture(int64_t ts) override; + bool retrieve(ftl::rgbd::Frame &frame) override; + bool isReady() override; Camera parameters(ftl::codecs::Channel chan) override; private: void updateParameters(); - LocalSource *lsrc_; + Device *lsrc_; Calibrate *calib_; int64_t capts_; @@ -54,8 +52,6 @@ class StereoVideoSource : public detail::Source { cv::cuda::Stream stream_; cv::cuda::Stream stream2_; - std::vector<Frame> frames_; - cv::Mat mask_l_; void init(const std::string &); diff --git a/components/rgbd-sources/test/source_unit.cpp b/components/rgbd-sources/test/source_unit.cpp index c1dbd76f5..c4d31a8fb 100644 --- a/components/rgbd-sources/test/source_unit.cpp +++ b/components/rgbd-sources/test/source_unit.cpp @@ -3,6 +3,7 @@ //---- Mocks ------------------------------------------------------------------- #include <ftl/rgbd/source.hpp> +#include "../src/basesource.hpp" #include <ftl/config.h> #include <nlohmann/json.hpp> @@ -30,105 +31,97 @@ class Player { namespace detail { -class ImageSource : public ftl::rgbd::detail::Source { +class ImageSource : public ftl::rgbd::BaseSourceImpl { public: - explicit ImageSource(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit ImageSource(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { last_type = "image"; } - ImageSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::detail::Source(host) { + ImageSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::BaseSourceImpl(host) { last_type = "image"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class ScreenCapture : public ftl::rgbd::detail::Source { +class ScreenCapture : public ftl::rgbd::BaseSourceImpl { public: - explicit ScreenCapture(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit ScreenCapture(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { last_type = "screen"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class StereoVideoSource : public ftl::rgbd::detail::Source { +class StereoVideoSource : public ftl::rgbd::BaseSourceImpl { public: - explicit StereoVideoSource(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit StereoVideoSource(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { last_type = "video"; } - StereoVideoSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::detail::Source(host) { + StereoVideoSource(ftl::rgbd::Source *host, const std::string &f) : ftl::rgbd::BaseSourceImpl(host) { last_type = "video"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class NetSource : public ftl::rgbd::detail::Source { +class NetSource : public ftl::rgbd::BaseSourceImpl { public: - explicit NetSource(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit NetSource(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { last_type = "net"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class SnapshotSource : public ftl::rgbd::detail::Source { +class SnapshotSource : public ftl::rgbd::BaseSourceImpl { public: - SnapshotSource(ftl::rgbd::Source *host, ftl::rgbd::Snapshot &r, const std::string &) : ftl::rgbd::detail::Source(host) { + SnapshotSource(ftl::rgbd::Source *host, ftl::rgbd::Snapshot &r, const std::string &) : ftl::rgbd::BaseSourceImpl(host) { last_type = "snapshot"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class FileSource : public ftl::rgbd::detail::Source { +class FileSource : public ftl::rgbd::BaseSourceImpl { public: - FileSource(ftl::rgbd::Source *host, ftl::rgbd::Player *r, int) : ftl::rgbd::detail::Source(host) { + FileSource(ftl::rgbd::Source *host, ftl::rgbd::Player *r, int) : ftl::rgbd::BaseSourceImpl(host) { last_type = "filesource"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class RealsenseSource : public ftl::rgbd::detail::Source { +class RealsenseSource : public ftl::rgbd::BaseSourceImpl { public: - explicit RealsenseSource(ftl::rgbd::Source *host) : ftl::rgbd::detail::Source(host) { + explicit RealsenseSource(ftl::rgbd::Source *host) : ftl::rgbd::BaseSourceImpl(host) { last_type = "realsense"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; -class MiddleburySource : public ftl::rgbd::detail::Source { +class MiddleburySource : public ftl::rgbd::BaseSourceImpl { public: - MiddleburySource(ftl::rgbd::Source *host, const std::string &dir) : ftl::rgbd::detail::Source(host) { + MiddleburySource(ftl::rgbd::Source *host, const std::string &dir) : ftl::rgbd::BaseSourceImpl(host) { last_type = "middlebury"; } bool capture(int64_t ts) { return true; } - bool retrieve() { return true; } - bool compute(int n, int b) { return true; }; + bool retrieve(ftl::rgbd::Frame &) { return true; } bool isReady() { return true; }; }; diff --git a/components/streams/src/parsers.cpp b/components/streams/src/parsers.cpp index 29a3350ec..1a8add33d 100644 --- a/components/streams/src/parsers.cpp +++ b/components/streams/src/parsers.cpp @@ -10,11 +10,11 @@ ftl::rgbd::Camera ftl::stream::parseCalibration(const ftl::codecs::Packet &pkt) auto unpacked = msgpack::unpack((const char*)pkt.data.data(), pkt.data.size()); unpacked.get().convert(params); - //LOG(INFO) << "Got Calibration: " - // << std::get<0>(params).width << "x" << std::get<0>(params).height - // << ", fx: " << std::get<0>(params).fx - // << ", cx: " << std::get<0>(params).cx - // << ", cy: " << std::get<0>(params).cy; + LOG(INFO) << "Got Calibration: " + << std::get<0>(params).width << "x" << std::get<0>(params).height + << ", fx: " << std::get<0>(params).fx + << ", cx: " << std::get<0>(params).cx + << ", cy: " << std::get<0>(params).cy; return std::get<0>(params); } diff --git a/components/streams/src/sender.cpp b/components/streams/src/sender.cpp index aff7cd9a1..37f23525c 100644 --- a/components/streams/src/sender.cpp +++ b/components/streams/src/sender.cpp @@ -229,8 +229,8 @@ void Sender::post(ftl::rgbd::FrameSet &fs) { for (auto c : frame.getChannels()) { if (selected.has(c)) { // FIXME: Sends high res colour, but receive end currently broken - auto cc = (c == Channel::Colour && frame.hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : c; - //auto cc = c; + //auto cc = (c == Channel::Colour && frame.hasChannel(Channel::ColourHighRes)) ? Channel::ColourHighRes : c; + auto cc = c; StreamPacket spkt; spkt.version = 4; @@ -300,14 +300,14 @@ void Sender::_encodeChannel(ftl::rgbd::FrameSet &fs, Channel c, bool reset) { uint32_t offset = 0; while (offset < fs.frames.size()) { Channel cc = c; - if ((cc == Channel::Colour) && fs.firstFrame().hasChannel(Channel::ColourHighRes)) { - cc = Channel::ColourHighRes; - } + //if ((cc == Channel::Colour) && fs.firstFrame().hasChannel(Channel::ColourHighRes)) { + // cc = Channel::ColourHighRes; + //} - if ((cc == Channel::Right) && fs.firstFrame().hasChannel(Channel::RightHighRes)) { - cc = Channel::RightHighRes; - fs.frames[offset].upload(cc); - } + //if ((cc == Channel::Right) && fs.firstFrame().hasChannel(Channel::RightHighRes)) { + // cc = Channel::RightHighRes; + // fs.frames[offset].upload(cc); + //} StreamPacket spkt; spkt.version = 4; -- GitLab