Merge pull request #20785 from smirnov-alexey:as/oak_backend

GAPI: Add OAK backend

* Initial tests and cmake integration

* Add a public header and change tests

* Stub initial empty template for the OAK backend

* WIP

* WIP

* WIP

* WIP

* Runtime dai hang debug

* Refactoring

* Fix hang and debug frame data

* Fix frame size

* Fix data size issue

* Move test code to sample

* tmp refactoring

* WIP: Code refactoring except for the backend

* WIP: Add non-camera sample

* Fix samples

* Backend refactoring wip

* Backend rework wip

* Backend rework wip

* Remove mat encoder

* Fix namespace

* Minor backend fixes

* Fix hetero sample and refactor backend

* Change linking logic in the backend

* Fix oak sample

* Fix working with ins/outs in OAK island

* Trying to fix nv12 problem

* Make both samples work

* Small refactoring

* Remove meta args

* WIP refactoring kernel API

* Change in/out args API for kernels

* Fix build

* Fix cmake warning

* Partially address review comments

* Partially address review comments

* Address remaining comments

* Add memory ownership

* Change pointer-to-pointer to reference-to-pointer

* Remove unnecessary reference wrappers

* Apply review comments

* Check that graph contains only one OAK island

* Minor refactoring

* Address review comments
This commit is contained in:
Alexey Smirnov 2022-01-18 01:56:01 +03:00 committed by GitHub
parent a1ec4ea3a9
commit f2d5d6d24e
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
10 changed files with 1155 additions and 2 deletions

View File

@ -45,6 +45,7 @@ file(GLOB gapi_ext_hdrs
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/fluid/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/gpu/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/infer/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/oak/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/ocl/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/own/*.hpp"
"${CMAKE_CURRENT_LIST_DIR}/include/opencv2/${name}/plaidml/*.hpp"
@ -127,6 +128,11 @@ set(gapi_srcs
src/backends/fluid/gfluidcore.cpp
src/backends/fluid/gfluidcore_func.dispatch.cpp
# OAK Backend (optional)
src/backends/oak/goak.cpp
src/backends/oak/goakbackend.cpp
src/backends/oak/goak_media_adapter.cpp
# OCL Backend (currently built-in)
src/backends/ocl/goclbackend.cpp
src/backends/ocl/goclkernel.cpp
@ -272,6 +278,14 @@ if(HAVE_FREETYPE)
ocv_target_include_directories(${the_module} PRIVATE ${FREETYPE_INCLUDE_DIRS})
endif()
if(HAVE_OAK)
ocv_target_compile_definitions(${the_module} PRIVATE -DHAVE_OAK)
if(TARGET opencv_test_gapi)
ocv_target_compile_definitions(opencv_test_gapi PRIVATE -DHAVE_OAK)
endif()
ocv_target_link_libraries(${the_module} PRIVATE depthai::core)
endif()
if(HAVE_PLAIDML)
ocv_target_compile_definitions(${the_module} PRIVATE -DHAVE_PLAIDML)
if(TARGET opencv_test_gapi)
@ -350,3 +364,13 @@ if(HAVE_GAPI_ONEVPL)
endif()
endif()
endif()
if(HAVE_OAK)
# FIXME: consider better solution
if(TARGET example_gapi_oak_rgb_camera_encoding)
ocv_target_compile_definitions(example_gapi_oak_rgb_camera_encoding PRIVATE -DHAVE_OAK)
endif()
if(TARGET example_gapi_oak_small_hetero_pipeline)
ocv_target_compile_definitions(example_gapi_oak_small_hetero_pipeline PRIVATE -DHAVE_OAK)
endif()
endif()

View File

@ -1,7 +1,8 @@
OCV_OPTION(WITH_ADE "Enable ADE framework (required for Graph API module)" ON)
OCV_OPTION(WITH_FREETYPE "Enable FreeType framework" OFF)
OCV_OPTION(WITH_PLAIDML "Include PlaidML2 support" OFF)
OCV_OPTION(WITH_FREETYPE "Enable FreeType framework" OFF)
OCV_OPTION(WITH_PLAIDML "Include PlaidML2 support" OFF)
OCV_OPTION(WITH_OAK "Include OpenCV AI Kit support" OFF)
if(NOT WITH_ADE)
return()
@ -39,3 +40,10 @@ if(WITH_GAPI_ONEVPL)
set(HAVE_GAPI_ONEVPL TRUE)
endif()
endif()
if(WITH_OAK)
find_package(depthai QUIET)
if(depthai_FOUND)
set(HAVE_OAK TRUE)
endif()
endif()

View File

@ -0,0 +1,131 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#ifndef OPENCV_GAPI_OAK_HPP
#define OPENCV_GAPI_OAK_HPP
#include <opencv2/gapi/garg.hpp> // IStreamSource
#include <opencv2/gapi/gkernel.hpp> // GKernelPackage
#include <opencv2/gapi/gstreaming.hpp> // GOptRunArgsP
namespace cv {
namespace gapi {
namespace oak {
// FIXME: copypasted from dai library
struct EncoderConfig {
/**
* Rate control mode specifies if constant or variable bitrate should be used (H264 / H265)
*/
enum class RateControlMode: int { CBR, VBR };
/**
* Encoding profile, H264, H265 or MJPEG
*/
enum class Profile: int { H264_BASELINE, H264_HIGH, H264_MAIN, H265_MAIN, MJPEG };
/**
* Specifies prefered bitrate (kb) of compressed output bitstream
*/
std::int32_t bitrate = 8000;
/**
* Every x number of frames a keyframe will be inserted
*/
std::int32_t keyframeFrequency = 30;
/**
* Specifies maximum bitrate (kb) of compressed output bitstream
*/
std::int32_t maxBitrate = 8000;
/**
* Specifies number of B frames to be inserted
*/
std::int32_t numBFrames = 0;
/**
* This options specifies how many frames are available in this nodes pool (can help if
* receiver node is slow at consuming
*/
std::uint32_t numFramesPool = 4;
/**
* Encoding profile, H264, H265 or MJPEG
*/
Profile profile = Profile::H265_MAIN;
/**
* Value between 0-100% (approximates quality)
*/
std::int32_t quality = 80;
/**
* Lossless mode ([M]JPEG only)
*/
bool lossless = false;
/**
* Rate control mode specifies if constant or variable bitrate should be used (H264 / H265)
*/
RateControlMode rateCtrlMode = RateControlMode::CBR;
/**
* Input and compressed output frame width
*/
std::int32_t width = 1920;
/**
* Input and compressed output frame height
*/
std::int32_t height = 1080;
/**
* Frame rate
*/
float frameRate = 30.0f;
};
G_API_OP(GEncFrame, <GArray<uint8_t>(GFrame, EncoderConfig)>, "org.opencv.oak.enc_frame") {
static GArrayDesc outMeta(const GFrameDesc&, const EncoderConfig&) {
return cv::empty_array_desc();
}
};
G_API_OP(GSobelXY, <GFrame(GFrame, const cv::Mat&, const cv::Mat&)>, "org.opencv.oak.sobelxy") {
static GFrameDesc outMeta(const GFrameDesc& in, const cv::Mat&, const cv::Mat&) {
return in;
}
};
GAPI_EXPORTS GArray<uint8_t> encode(const GFrame& in, const EncoderConfig&);
GAPI_EXPORTS GFrame sobelXY(const GFrame& in,
const cv::Mat& hk,
const cv::Mat& vk);
// OAK backend & kernels ////////////////////////////////////////////////////////
GAPI_EXPORTS cv::gapi::GBackend backend();
GAPI_EXPORTS cv::gapi::GKernelPackage kernels();
// Camera object ///////////////////////////////////////////////////////////////
struct GAPI_EXPORTS ColorCameraParams {};
class GAPI_EXPORTS ColorCamera: public cv::gapi::wip::IStreamSource {
cv::MediaFrame m_dummy;
virtual bool pull(cv::gapi::wip::Data &data) override;
virtual GMetaArg descr_of() const override;
public:
ColorCamera();
};
} // namespace oak
} // namespace gapi
namespace detail {
template<> struct CompileArgTag<gapi::oak::ColorCameraParams> {
static const char* tag() { return "gapi.oak.colorCameraParams"; }
};
template<> struct CompileArgTag<gapi::oak::EncoderConfig> {
static const char* tag() { return "gapi.oak.encoderConfig"; }
};
} // namespace detail
} // namespace cv
#endif // OPENCV_GAPI_OAK_HPP

View File

@ -0,0 +1,70 @@
#include <fstream>
#include <opencv2/gapi.hpp>
#include <opencv2/gapi/core.hpp>
#include <opencv2/gapi/gframe.hpp>
#include <opencv2/gapi/oak/oak.hpp>
#include <opencv2/gapi/streaming/format.hpp> // BGR accessor
#include <opencv2/highgui.hpp> // CommandLineParser
const std::string keys =
"{ h help | | Print this help message }"
"{ output | output.h265 | Path to the output .h265 video file }";
#ifdef HAVE_OAK
int main(int argc, char *argv[]) {
cv::CommandLineParser cmd(argc, argv, keys);
if (cmd.has("help")) {
cmd.printMessage();
return 0;
}
const std::string output_name = cmd.get<std::string>("output");
cv::gapi::oak::EncoderConfig cfg;
cfg.profile = cv::gapi::oak::EncoderConfig::Profile::H265_MAIN;
cv::GFrame in;
cv::GArray<uint8_t> encoded = cv::gapi::oak::encode(in, cfg);
auto args = cv::compile_args(cv::gapi::oak::ColorCameraParams{}, cv::gapi::oak::kernels());
auto pipeline = cv::GComputation(cv::GIn(in), cv::GOut(encoded)).compileStreaming(std::move(args));
// Graph execution /////////////////////////////////////////////////////////
pipeline.setSource(cv::gapi::wip::make_src<cv::gapi::oak::ColorCamera>());
pipeline.start();
std::vector<uint8_t> out_h265_data;
std::ofstream out_h265_file;
out_h265_file.open(output_name, std::ofstream::out | std::ofstream::binary | std::ofstream::trunc);
// Pull 300 frames from the camera
uint32_t frames = 300;
uint32_t pulled = 0;
while (pipeline.pull(cv::gout(out_h265_data))) {
if (out_h265_file.is_open()) {
out_h265_file.write(reinterpret_cast<const char*>(out_h265_data.data()),
out_h265_data.size());
}
if (pulled++ == frames) {
pipeline.stop();
break;
}
}
std::cout << "Pipeline finished: " << output_name << " file has been written." << std::endl;
}
#else // HAVE_OAK
int main() {
GAPI_Assert(false && "Built without OAK support");
return -1;
}
#endif // HAVE_OAK

View File

@ -0,0 +1,69 @@
#include <opencv2/gapi.hpp>
#include <opencv2/gapi/core.hpp>
#include <opencv2/gapi/cpu/core.hpp>
#include <opencv2/gapi/gframe.hpp>
#include <opencv2/gapi/media.hpp>
#include <opencv2/gapi/oak/oak.hpp>
#include <opencv2/gapi/streaming/format.hpp> // BGR accessor
#include <opencv2/highgui.hpp> // CommandLineParser
const std::string keys =
"{ h help | | Print this help message }"
"{ output | output.png | Path to the output file }";
#ifdef HAVE_OAK
int main(int argc, char *argv[]) {
cv::CommandLineParser cmd(argc, argv, keys);
if (cmd.has("help")) {
cmd.printMessage();
return 0;
}
const std::string output_name = cmd.get<std::string>("output");
std::vector<int> h = {1, 0, -1,
2, 0, -2,
1, 0, -1};
std::vector<int> v = { 1, 2, 1,
0, 0, 0,
-1, -2, -1};
cv::Mat hk(3, 3, CV_32SC1, h.data());
cv::Mat vk(3, 3, CV_32SC1, v.data());
// Heterogeneous pipeline:
// OAK camera -> Sobel -> streaming accessor (CPU)
cv::GFrame in;
cv::GFrame sobel = cv::gapi::oak::sobelXY(in, hk, vk);
// Default camera and then sobel work only with nv12 format
cv::GMat out = cv::gapi::streaming::Y(sobel);
auto args = cv::compile_args(cv::gapi::oak::ColorCameraParams{},
cv::gapi::oak::kernels());
auto pipeline = cv::GComputation(cv::GIn(in), cv::GOut(out)).compileStreaming(std::move(args));
// Graph execution /////////////////////////////////////////////////////////
cv::Mat out_mat(1920, 1080, CV_8UC1);
pipeline.setSource(cv::gapi::wip::make_src<cv::gapi::oak::ColorCamera>());
pipeline.start();
// pull 1 frame
pipeline.pull(cv::gout(out_mat));
cv::imwrite(output_name, out_mat);
std::cout << "Pipeline finished: " << output_name << " file has been written." << std::endl;
}
#else // HAVE_OAK
int main() {
GAPI_Assert(false && "Built without OAK support");
return -1;
}
#endif // HAVE_OAK

View File

@ -0,0 +1,47 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#include <opencv2/gapi/oak/oak.hpp>
#include <opencv2/gapi/cpu/gcpukernel.hpp>
#include "oak_media_adapter.hpp"
#include <thread>
#include <chrono>
namespace cv {
namespace gapi {
namespace oak {
GArray<uint8_t> encode(const GFrame& in, const EncoderConfig& cfg) {
return GEncFrame::on(in, cfg);
}
GFrame sobelXY(const GFrame& in, const cv::Mat& hk, const cv::Mat& vk) {
return GSobelXY::on(in, hk, vk);
}
// This is a dummy oak::ColorCamera class that just makes our pipelining
// machinery work. The real data comes from the physical camera which
// is handled by DepthAI library.
ColorCamera::ColorCamera()
: m_dummy(cv::MediaFrame::Create<cv::gapi::oak::OAKMediaAdapter>()) {
}
bool ColorCamera::pull(cv::gapi::wip::Data &data) {
// FIXME: Avoid passing this formal frame to the pipeline
std::this_thread::sleep_for(std::chrono::milliseconds(10));
data = m_dummy;
return true;
}
cv::GMetaArg ColorCamera::descr_of() const {
return cv::GMetaArg{cv::descr_of(m_dummy)};
}
} // namespace oak
} // namespace gapi
} // namespace cv

View File

@ -0,0 +1,32 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#include "oak_media_adapter.hpp"
namespace cv {
namespace gapi {
namespace oak {
OAKMediaAdapter::OAKMediaAdapter(cv::Size sz, cv::MediaFormat fmt, std::vector<uint8_t>&& buffer) {
GAPI_Assert(fmt == cv::MediaFormat::NV12 && "OAKMediaAdapter only supports NV12 format for now");
m_sz = sz;
m_fmt = fmt;
m_buffer = buffer;
}
MediaFrame::View OAKMediaAdapter::OAKMediaAdapter::access(MediaFrame::Access) {
uint8_t* y_ptr = m_buffer.data();
uint8_t* uv_ptr = m_buffer.data() + static_cast<long>(m_buffer.size() / 3 * 2);
return MediaFrame::View{cv::MediaFrame::View::Ptrs{y_ptr, uv_ptr},
cv::MediaFrame::View::Strides{static_cast<long unsigned int>(m_sz.width),
static_cast<long unsigned int>(m_sz.width)}};
}
cv::GFrameDesc OAKMediaAdapter::OAKMediaAdapter::meta() const { return {m_fmt, m_sz}; }
} // namespace oak
} // namespace gapi
} // namespace cv

View File

@ -0,0 +1,711 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#include <opencv2/gapi/gkernel.hpp> // GKernelPackage
#ifdef HAVE_OAK
#include <cstring>
#include <unordered_set>
#include <algorithm> // any_of
#include <functional> // reference_wrapper
#include <ade/util/zip_range.hpp>
#include <api/gbackend_priv.hpp>
#include <backends/common/gbackend.hpp>
#include <opencv2/gapi/streaming/meta.hpp> // streaming::meta_tag
#include "depthai/depthai.hpp"
#include <opencv2/gapi/oak/oak.hpp>
#include "oak_media_adapter.hpp"
namespace cv { namespace gimpl {
// Forward declaration
class GOAKContext;
struct OAKNodeInfo;
class GOAKExecutable final: public GIslandExecutable {
friend class GOAKContext;
virtual void run(std::vector<InObj>&&,
std::vector<OutObj>&&) override {
GAPI_Assert(false && "Not implemented");
}
virtual void run(GIslandExecutable::IInput &in,
GIslandExecutable::IOutput &out) override;
void LinkToParents(ade::NodeHandle handle);
class ExtractTypeHelper : protected dai::Node {
public:
using Input = dai::Node::Input;
using Output = dai::Node::Output;
using InputPtr = dai::Node::Input*;
using OutputPtr = dai::Node::Output*;
};
struct OAKNodeInfo {
std::shared_ptr<dai::Node> node = nullptr;
std::vector<ExtractTypeHelper::InputPtr> inputs = {};
std::vector<ExtractTypeHelper::OutputPtr> outputs = {};
};
struct OAKOutQueueInfo {
std::shared_ptr<dai::node::XLinkOut> xlink_output;
std::shared_ptr<dai::DataOutputQueue> out_queue;
std::string out_queue_name;
};
cv::GArg packInArg(const GArg &arg, std::vector<ExtractTypeHelper::InputPtr>& oak_ins);
void packOutArg(const RcDesc &rc, std::vector<ExtractTypeHelper::OutputPtr>& oak_outs);
const ade::Graph& m_g;
GModel::ConstGraph m_gm;
cv::GCompileArgs m_args;
std::unordered_map<ade::NodeHandle,
OAKNodeInfo,
ade::HandleHasher<ade::Node>> m_oak_nodes;
// Will be reworked later when XLinkIn will be introduced as input
std::shared_ptr<dai::node::ColorCamera> m_camera_input;
cv::Size m_camera_size;
// Backend outputs
std::vector<OAKOutQueueInfo> m_out_queues;
// Backend inputs
std::vector<std::pair<std::string, dai::Buffer>> m_in_queues;
// Note: dai::Pipeline should be the only one for the whole pipeline,
// so there is no way to insert any non-OAK node in graph between other OAK nodes.
// The only heterogeneous case possible is if we insert other backends after or before
// OAK island.
std::unique_ptr<dai::Device> m_device;
std::unique_ptr<dai::Pipeline> m_pipeline;
public:
GOAKExecutable(const ade::Graph& g,
const cv::GCompileArgs& args,
const std::vector<ade::NodeHandle>& nodes,
const std::vector<cv::gimpl::Data>& ins_data,
const std::vector<cv::gimpl::Data>& outs_data);
~GOAKExecutable() = default;
// FIXME: could it reshape?
virtual bool canReshape() const override { return false; }
virtual void reshape(ade::Graph&, const GCompileArgs&) override {
GAPI_Assert(false && "GOAKExecutable::reshape() is not supported");
}
virtual void handleNewStream() override;
virtual void handleStopStream() override;
};
class GOAKContext {
public:
// FIXME: make private?
using Input = GOAKExecutable::ExtractTypeHelper::Input;
using Output = GOAKExecutable::ExtractTypeHelper::Output;
using InputPtr = GOAKExecutable::ExtractTypeHelper::Input*;
using OutputPtr = GOAKExecutable::ExtractTypeHelper::Output*;
GOAKContext(const std::unique_ptr<dai::Pipeline>& pipeline,
const cv::Size& camera_size,
std::vector<cv::GArg>& args,
std::vector<OutputPtr>& results);
// Generic accessor API
template<typename T>
T& inArg(int input) { return m_args.at(input).get<T>(); }
// FIXME: consider not using raw pointers
InputPtr& in(int input);
OutputPtr& out(int output);
const std::unique_ptr<dai::Pipeline>& pipeline();
const cv::Size& camera_size() const;
private:
const std::unique_ptr<dai::Pipeline>& m_pipeline;
const cv::Size& m_camera_size;
std::vector<cv::GArg>& m_args;
std::vector<OutputPtr>& m_outputs;
};
GOAKContext::GOAKContext(const std::unique_ptr<dai::Pipeline>& pipeline,
const cv::Size& camera_size,
std::vector<cv::GArg>& args,
std::vector<OutputPtr>& results)
: m_pipeline(pipeline), m_camera_size(camera_size), m_args(args), m_outputs(results) {}
const std::unique_ptr<dai::Pipeline>& GOAKContext::pipeline() {
return m_pipeline;
}
const cv::Size& GOAKContext::camera_size() const {
return m_camera_size;
}
GOAKContext::InputPtr& GOAKContext::in(int input) {
return inArg<std::reference_wrapper<GOAKContext::InputPtr>>(input).get();
}
GOAKContext::OutputPtr& GOAKContext::out(int output) {
return m_outputs.at(output);
}
namespace detail {
template<class T> struct get_in;
template<> struct get_in<cv::GFrame> {
static GOAKContext::InputPtr& get(GOAKContext &ctx, int idx) { return ctx.in(idx); }
};
template<class T> struct get_in {
static T get(GOAKContext &ctx, int idx) { return ctx.inArg<T>(idx); }
};
// FIXME: add support of other types
template<class T> struct get_out;
template<> struct get_out<cv::GFrame> {
static GOAKContext::OutputPtr& get(GOAKContext &ctx, int idx) { return ctx.out(idx); }
};
template<typename U> struct get_out<cv::GArray<U>> {
static GOAKContext::OutputPtr& get(GOAKContext &ctx, int idx) { return ctx.out(idx); }
};
// FIXME: add support of other types
struct OAKKernelParams {
const std::unique_ptr<dai::Pipeline>& pipeline;
const cv::Size& camera_size;
std::vector<std::pair<std::string, dai::Buffer>>& m_in_queues;
};
template<typename, typename, typename>
struct OAKCallHelper;
template<typename Impl, typename... Ins, typename... Outs>
struct OAKCallHelper<Impl, std::tuple<Ins...>, std::tuple<Outs...> > {
template<int... IIs, int... OIs>
static std::shared_ptr<dai::Node> construct_impl( GOAKContext &ctx
, std::vector<std::pair<std::string,
dai::Buffer>>& in_queues_params
, cv::detail::Seq<IIs...>
, cv::detail::Seq<OIs...>) {
return Impl::put(OAKKernelParams{ctx.pipeline(),
ctx.camera_size(),
in_queues_params},
get_in<Ins>::get(ctx, IIs)...,
get_out<Outs>::get(ctx, OIs)...);
}
static std::shared_ptr<dai::Node> construct(GOAKContext &ctx,
std::vector<std::pair<std::string,
dai::Buffer>>& in_queues_params) {
return construct_impl(ctx,
in_queues_params,
typename cv::detail::MkSeq<sizeof...(Ins)>::type(),
typename cv::detail::MkSeq<sizeof...(Outs)>::type());
}
};
} // namespace detail
struct GOAKKernel {
using F = std::function<std::shared_ptr<dai::Node>(GOAKContext&,
std::vector<std::pair<std::string, dai::Buffer>>&)>;
explicit GOAKKernel(const F& f) : m_put_f(f) {}
const F m_put_f;
};
struct OAKComponent
{
static const char *name() { return "OAK Component"; }
GOAKKernel k;
};
}} // namespace gimpl // namespace cv
using OAKGraph = ade::TypedGraph
< cv::gimpl::OAKComponent
// FIXME: extend
>;
using ConstOAKGraph = ade::ConstTypedGraph
< cv::gimpl::OAKComponent
// FIXME: extend
>;
// This function links dai operation nodes - parent's output to child's input.
// It utilizes G-API graph to search for operation's node it's previous operation in graph
// when links them in dai graph.
void cv::gimpl::GOAKExecutable::LinkToParents(ade::NodeHandle handle)
{
ade::NodeHandle parent;
for (const auto& data_nh : handle.get()->inNodes()) {
// Data node has only 1 input
GAPI_Assert(data_nh.get()->inNodes().size() == 1);
parent = data_nh.get()->inNodes().front();
// Assuming that OAK nodes are aligned for linking.
// FIXME: potential rework might be needed then
// counterexample is found.
GAPI_Assert(m_oak_nodes.at(handle).inputs.size() ==
m_oak_nodes.at(parent).outputs.size() &&
"Internal OAK nodes are not aligned for linking");
for (auto && it : ade::util::zip(ade::util::toRange(m_oak_nodes.at(parent).outputs),
ade::util::toRange(m_oak_nodes.at(handle).inputs)))
{
auto &out = std::get<0>(it);
auto &in = std::get<1>(it);
out->link(*in);
}
}
}
cv::GArg
cv::gimpl::GOAKExecutable::packInArg(const GArg &arg,
std::vector<ExtractTypeHelper::InputPtr>& oak_ins) {
if (arg.kind != cv::detail::ArgKind::GOBJREF) {
GAPI_Assert( arg.kind != cv::detail::ArgKind::GMAT
&& arg.kind != cv::detail::ArgKind::GSCALAR
&& arg.kind != cv::detail::ArgKind::GARRAY
&& arg.kind != cv::detail::ArgKind::GOPAQUE
&& arg.kind != cv::detail::ArgKind::GFRAME);
// All other cases - pass as-is, with no transformations to
// GArg contents.
return const_cast<cv::GArg&>(arg);
}
const cv::gimpl::RcDesc &ref = arg.get<cv::gimpl::RcDesc>();
switch (ref.shape) {
case GShape::GFRAME:
oak_ins.push_back(nullptr);
return GArg(std::reference_wrapper<ExtractTypeHelper::InputPtr>(oak_ins.back()));
break;
default:
util::throw_error(std::logic_error("Unsupported GShape type in OAK backend"));
break;
}
}
void cv::gimpl::GOAKExecutable::packOutArg(const RcDesc &rc,
std::vector<ExtractTypeHelper::OutputPtr>& oak_outs) {
switch (rc.shape) {
case GShape::GFRAME:
oak_outs.push_back(nullptr);
break;
case GShape::GARRAY:
oak_outs.push_back(nullptr);
break;
default:
util::throw_error(std::logic_error("Unsupported GShape type in OAK backend"));
break;
}
}
cv::gimpl::GOAKExecutable::GOAKExecutable(const ade::Graph& g,
const cv::GCompileArgs &args,
const std::vector<ade::NodeHandle>& nodes,
const std::vector<cv::gimpl::Data>& ins_data,
const std::vector<cv::gimpl::Data>& outs_data)
: m_g(g), m_gm(m_g), m_args(args),
m_device(nullptr), m_pipeline(new dai::Pipeline)
{
// FIXME: currently OAK backend only works with camera as input,
// so it must be a single object
GAPI_Assert(ins_data.size() == 1);
// Check that there is only one OAK island in graph since there
// can only be one instance of dai::Pipeline in the application
auto isl_graph = m_gm.metadata().get<IslandModel>().model;
GIslandModel::Graph gim(*isl_graph);
size_t oak_islands = 0;
for (const auto& nh : gim.nodes())
{
if (gim.metadata(nh).get<NodeKind>().k == NodeKind::ISLAND)
{
const auto isl = gim.metadata(nh).get<FusedIsland>().object;
if (isl->backend() == cv::gapi::oak::backend())
{
++oak_islands;
}
if (oak_islands > 1) {
util::throw_error
(std::logic_error
("There can only be one OAK island in graph"));
}
}
}
// FIXME: change the hard-coded behavior (XLinkIn path)
auto camRgb = m_pipeline->create<dai::node::ColorCamera>();
// FIXME: extract camera compile arguments here and properly convert them for dai
camRgb->setBoardSocket(dai::CameraBoardSocket::RGB);
camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
// Set camera output. Fixme: consider working with other camera outputs
m_camera_input = camRgb;
// FIXME: change when other camera censors are introduced
std::tuple<int, int> video_size = camRgb->getVideoSize();
m_camera_size = cv::Size{std::get<0>(video_size), std::get<1>(video_size)};
// Prepare XLinkOut nodes for each output object in graph
for (size_t i = 0; i < outs_data.size(); ++i) {
auto xout = m_pipeline->create<dai::node::XLinkOut>();
std::string xout_name = "xout" + std::to_string(i);
xout->setStreamName(xout_name);
m_out_queues.push_back({xout, nullptr, xout_name});
}
// Create OAK node for each node in this backend
for (const auto& nh : nodes) {
if (m_gm.metadata(nh).get<NodeType>().t == NodeType::OP) {
const auto& op = m_gm.metadata(nh).get<Op>();
const auto &u = ConstOAKGraph(m_g).metadata(nh).get<OAKComponent>();
// pass kernel input args and compile args to prepare OAK node and
// store it to link later
m_oak_nodes[nh] = {};
m_oak_nodes.at(nh).inputs.reserve(op.args.size());
m_oak_nodes.at(nh).outputs.reserve(op.outs.size());
std::vector<cv::GArg> in_ctx_args;
in_ctx_args.reserve(op.args.size());
for (auto &op_arg : op.args) in_ctx_args.push_back(packInArg(op_arg,
m_oak_nodes.at(nh).inputs));
for (auto &&op_out : op.outs) packOutArg(op_out, m_oak_nodes.at(nh).outputs);
GAPI_Assert(!m_oak_nodes.at(nh).inputs.empty());
GAPI_Assert(!m_oak_nodes.at(nh).outputs.empty());
GOAKContext ctx(m_pipeline, m_camera_size, in_ctx_args, m_oak_nodes.at(nh).outputs);
m_oak_nodes.at(nh).node = u.k.m_put_f(ctx, m_in_queues);
GAPI_Assert(m_oak_nodes.at(nh).node != nullptr);
// Check that all inputs and outputs are properly filled after constructing kernels
// to then link it together
// FIXME: add more logging
const auto& node = m_oak_nodes.at(nh);
if (std::any_of(node.inputs.cbegin(), node.inputs.cend(),
[](ExtractTypeHelper::InputPtr ptr) {
return ptr == nullptr;
})) {
GAPI_Assert(false && "DAI input are not set");
}
if (std::any_of(node.outputs.cbegin(), node.outputs.cend(),
[](ExtractTypeHelper::OutputPtr ptr) {
return ptr == nullptr;
})) {
GAPI_Assert(false && "DAI outputs are not set");
}
}
}
// Prepare nodes for linking
std::unordered_set<ade::NodeHandle,
ade::HandleHasher<ade::Node>> in_nodes;
std::unordered_set<ade::NodeHandle,
ade::HandleHasher<ade::Node>> out_nodes;
std::unordered_set<ade::NodeHandle,
ade::HandleHasher<ade::Node>> inter_nodes;
// TODO: optimize this loop
for (const auto& node : m_oak_nodes) {
auto nh = node.first;
// Fill input op nodes
for (const auto& d : ins_data) {
for (const auto& indata : nh.get()->inNodes()) {
auto rc = m_gm.metadata(indata).get<cv::gimpl::Data>().rc;
if (rc == d.rc) {
in_nodes.insert(nh);
}
}
}
// Fill output op nodes
for (const auto& d : outs_data) {
for (const auto& outdata : nh.get()->outNodes()) {
auto rc = m_gm.metadata(outdata).get<cv::gimpl::Data>().rc;
if (rc == d.rc) {
out_nodes.insert(nh);
}
}
}
// Fill internal op nodes
if (in_nodes.find(nh) == in_nodes.end() &&
out_nodes.find(nh) == in_nodes.end()) {
inter_nodes.insert(nh);
}
}
// Properly link all nodes
// 1. Link input nodes to camera
for (const auto& nh : in_nodes) {
GAPI_Assert(m_oak_nodes.at(nh).inputs.size() == 1);
// FIXME: covert other camera outputs
m_camera_input->video.link(*(m_oak_nodes.at(nh).inputs[0]));
}
// 2. Link output nodes to XLinkOut nodes
size_t out_counter = 0;
for (const auto& nh : out_nodes) {
GAPI_Assert(out_counter + m_oak_nodes.at(nh).outputs.size() <= m_out_queues.size());
for (const auto& out : m_oak_nodes.at(nh).outputs) {
out->link(m_out_queues[out_counter++].xlink_output->input);
}
// Input nodes in OAK doesn't have parent operation - just camera (for now)
if (in_nodes.find(nh) == in_nodes.end()) {
LinkToParents(nh);
}
}
// 3. Link internal nodes to their parents
for (const auto& nh : inter_nodes) {
// Input nodes in OAK doesn't have parent operation - just camera (for now)
if (in_nodes.find(nh) == in_nodes.end()) {
LinkToParents(nh);
}
}
m_device = std::unique_ptr<dai::Device>(new dai::Device(*m_pipeline));
// Prepare OAK output queues
GAPI_Assert(m_out_queues.size() == outs_data.size());
for (const auto out_it : ade::util::indexed(outs_data))
{
auto& q = m_out_queues[ade::util::index(out_it)];
GAPI_Assert(q.out_queue == nullptr); // shouldn't be not filled till this point
// FIXME: add queue parameters
// Currently: 30 - max DAI queue capacity, true - blocking queue
q.out_queue = m_device->getOutputQueue(q.out_queue_name, 30, true);
}
}
void cv::gimpl::GOAKExecutable::handleNewStream() {
// do nothing
}
void cv::gimpl::GOAKExecutable::handleStopStream() {
// do nothing
}
void cv::gimpl::GOAKExecutable::run(GIslandExecutable::IInput &in,
GIslandExecutable::IOutput &out) {
const auto in_msg = in.get();
if (cv::util::holds_alternative<cv::gimpl::EndOfStream>(in_msg)) {
out.post(cv::gimpl::EndOfStream{});
return;
}
for (const auto& in_q : m_in_queues) {
auto q = m_device->getInputQueue(in_q.first);
q->send(in_q.second);
}
for (size_t i = 0; i < m_out_queues.size(); ++i) {
auto q = m_out_queues[i].out_queue;
// TODO: support other DAI types if needed
// Note: we utilize getData() method that returns std::vector of data
// on which we gain ownership
auto oak_frame = q->get<dai::ImgFrame>();
auto out_arg = out.get(i);
switch(out_arg.index()) {
case cv::GRunArgP::index_of<cv::MediaFrame*>():
// FIXME: hard-coded NV12
*cv::util::get<cv::MediaFrame*>(out_arg) =
cv::MediaFrame::Create<cv::gapi::oak::OAKMediaAdapter>(
cv::Size(static_cast<int>(oak_frame->getWidth()),
static_cast<int>(oak_frame->getHeight())),
cv::MediaFormat::NV12,
std::move(oak_frame->getData()));
break;
case cv::GRunArgP::index_of<cv::detail::VectorRef>():
cv::util::get<cv::detail::VectorRef>(out_arg).wref<uint8_t>() = std::move(oak_frame->getData());
break;
// FIXME: Add support for remaining types
default:
GAPI_Assert(false && "Unsupported type in OAK backend");
}
using namespace cv::gapi::streaming::meta_tag;
cv::GRunArg::Meta meta;
meta[timestamp] = oak_frame->getTimestamp();
meta[seq_id] = oak_frame->getSequenceNum();
out.meta(out_arg, meta);
out.post(std::move(out_arg));
}
}
// Built-in kernels for OAK /////////////////////////////////////////////////////
class GOAKBackendImpl final : public cv::gapi::GBackend::Priv {
virtual void unpackKernel(ade::Graph &graph,
const ade::NodeHandle &op_node,
const cv::GKernelImpl &impl) override {
OAKGraph gm(graph);
const auto &kimpl = cv::util::any_cast<cv::gimpl::GOAKKernel>(impl.opaque);
gm.metadata(op_node).set(cv::gimpl::OAKComponent{kimpl});
}
virtual EPtr compile(const ade::Graph &graph,
const cv::GCompileArgs &args,
const std::vector<ade::NodeHandle> &nodes,
const std::vector<cv::gimpl::Data>& ins_data,
const std::vector<cv::gimpl::Data>& outs_data) const override {
cv::gimpl::GModel::ConstGraph gm(graph);
// FIXME: pass streaming/non-streaming option to support non-camera case
// NB: how could we have non-OAK source in streaming mode, then OAK backend in
// streaming mode but without camera input?
if (!gm.metadata().contains<cv::gimpl::Streaming>()) {
GAPI_Assert(false && "OAK backend only supports Streaming mode for now");
}
return EPtr{new cv::gimpl::GOAKExecutable(graph, args, nodes, ins_data, outs_data)};
}
};
cv::gapi::GBackend cv::gapi::oak::backend() {
static cv::gapi::GBackend this_backend(std::make_shared<GOAKBackendImpl>());
return this_backend;
}
namespace cv {
namespace gimpl {
namespace oak {
namespace {
static dai::VideoEncoderProperties::Profile convertEncProfile(cv::gapi::oak::EncoderConfig::Profile pf) {
switch (pf) {
case cv::gapi::oak::EncoderConfig::Profile::H264_BASELINE:
return dai::VideoEncoderProperties::Profile::H264_BASELINE;
case cv::gapi::oak::EncoderConfig::Profile::H264_HIGH:
return dai::VideoEncoderProperties::Profile::H264_HIGH;
case cv::gapi::oak::EncoderConfig::Profile::H264_MAIN:
return dai::VideoEncoderProperties::Profile::H264_MAIN;
case cv::gapi::oak::EncoderConfig::Profile::H265_MAIN:
return dai::VideoEncoderProperties::Profile::H265_MAIN;
case cv::gapi::oak::EncoderConfig::Profile::MJPEG:
return dai::VideoEncoderProperties::Profile::MJPEG;
default:
// basically unreachable
GAPI_Assert("Unsupported encoder profile");
return {};
}
}
} // anonymous namespace
// Kernels ///////////////////////////////////////////////////////////////
template<class Impl, class K>
class GOAKKernelImpl: public detail::OAKCallHelper<Impl, typename K::InArgs, typename K::OutArgs>
, public cv::detail::KernelTag {
using P = detail::OAKCallHelper<Impl, typename K::InArgs, typename K::OutArgs>;
public:
using API = K;
static cv::gapi::GBackend backend() { return cv::gapi::oak::backend(); }
static GOAKKernel kernel() { return GOAKKernel(&P::construct); }
};
#define GAPI_OAK_KERNEL(Name, API) \
struct Name: public cv::gimpl::oak::GOAKKernelImpl<Name, API>
namespace {
GAPI_OAK_KERNEL(GOAKEncFrame, cv::gapi::oak::GEncFrame) {
static std::shared_ptr<dai::Node> put(const cv::gimpl::detail::OAKKernelParams& params,
GOAKContext::InputPtr& in,
const cv::gapi::oak::EncoderConfig& cfg,
GOAKContext::OutputPtr& out) {
auto videoEnc = params.pipeline->create<dai::node::VideoEncoder>();
// FIXME: convert all the parameters to dai
videoEnc->setDefaultProfilePreset(cfg.width, cfg.height,
cfg.frameRate,
convertEncProfile(cfg.profile));
in = &(videoEnc->input);
out = &(videoEnc->bitstream);
return videoEnc;
}
};
GAPI_OAK_KERNEL(GOAKSobelXY, cv::gapi::oak::GSobelXY) {
static std::shared_ptr<dai::Node> put(const cv::gimpl::detail::OAKKernelParams& params,
GOAKContext::InputPtr& in,
const cv::Mat& hk,
const cv::Mat& vk,
GOAKContext::OutputPtr& out) {
auto edgeDetector = params.pipeline->create<dai::node::EdgeDetector>();
edgeDetector->setMaxOutputFrameSize(params.camera_size.width * params.camera_size.height);
auto xinEdgeCfg = params.pipeline->create<dai::node::XLinkIn>();
xinEdgeCfg->setStreamName("sobel_cfg");
auto mat2vec = [&](cv::Mat m) {
std::vector<std::vector<int>> v(m.rows);
for (int i = 0; i < m.rows; ++i)
{
m.row(i).reshape(1,1).copyTo(v[i]);
}
return v;
};
dai::EdgeDetectorConfig cfg;
cfg.setSobelFilterKernels(mat2vec(hk), mat2vec(vk));
xinEdgeCfg->out.link(edgeDetector->inputConfig);
params.m_in_queues.push_back({"sobel_cfg", cfg});
in = &(edgeDetector->inputImage);
out = &(edgeDetector->outputImage);
return edgeDetector;
}
};
} // anonymous namespace
} // namespace oak
} // namespace gimpl
} // namespace cv
namespace cv {
namespace gapi {
namespace oak {
cv::gapi::GKernelPackage kernels() {
return cv::gapi::kernels< cv::gimpl::oak::GOAKEncFrame
, cv::gimpl::oak::GOAKSobelXY
>();
}
} // namespace oak
} // namespace gapi
} // namespace cv
#else
namespace cv {
namespace gapi {
namespace oak {
cv::gapi::GKernelPackage kernels();
cv::gapi::GKernelPackage kernels() {
GAPI_Assert(false && "Built without OAK support");
return {};
}
} // namespace oak
} // namespace gapi
} // namespace cv
#endif // HAVE_OAK

View File

@ -0,0 +1,35 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#ifndef OPENCV_GAPI_OAK_MEDIA_ADAPTER_HPP
#define OPENCV_GAPI_OAK_MEDIA_ADAPTER_HPP
#include <memory>
#include <opencv2/gapi/media.hpp>
namespace cv {
namespace gapi {
namespace oak {
class GAPI_EXPORTS OAKMediaAdapter final : public cv::MediaFrame::IAdapter {
public:
OAKMediaAdapter() = default;
OAKMediaAdapter(cv::Size sz, cv::MediaFormat fmt, std::vector<uint8_t>&& buffer);
cv::GFrameDesc meta() const override;
cv::MediaFrame::View access(cv::MediaFrame::Access) override;
~OAKMediaAdapter() = default;
private:
cv::Size m_sz;
cv::MediaFormat m_fmt;
std::vector<uint8_t> m_buffer;
};
} // namespace oak
} // namespace gapi
} // namespace cv
#endif // OPENCV_GAPI_OAK_MEDIA_ADAPTER_HPP

View File

@ -0,0 +1,26 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html.
//
// Copyright (C) 2021 Intel Corporation
#include "../test_precomp.hpp"
#ifdef HAVE_OAK
#include <opencv2/gapi/oak/oak.hpp>
namespace opencv_test
{
// FIXME: consider a better solution
TEST(OAK, Available)
{
cv::GFrame in;
auto out = cv::gapi::oak::encode(in, {});
auto args = cv::compile_args(cv::gapi::oak::ColorCameraParams{}, cv::gapi::oak::kernels());
auto pipeline = cv::GComputation(cv::GIn(in), cv::GOut(out)).compileStreaming(std::move(args));
}
} // opencv_test
#endif // HAVE_OAK