Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Release v2.10.0 #201

Merged
merged 61 commits into from
Aug 24, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
61 commits
Select commit Hold shift + click to select a range
b4d9405
POC: Feature tracker node
SzabolcsGergely Jul 6, 2021
aee34d1
Add FeatureTracker node; add cpp example
SzabolcsGergely Jul 9, 2021
dc90e69
Update trackbar naming
SzabolcsGergely Jul 9, 2021
fadbd68
Remove leftover code
SzabolcsGergely Jul 9, 2021
2f3dc1c
Update FW with multi instance support
SzabolcsGergely Jul 13, 2021
a67a24b
Separate Queue handling from core API
kunaltyagi Jun 8, 2021
cfb2409
Separate Device and DeviceBase, expose StreamPacketParser
kunaltyagi Jun 8, 2021
3a69a6b
Move items around in startPipeline
kunaltyagi Jun 9, 2021
8be94a3
Make the virtual functios protected and public functions non-virtual
kunaltyagi Jun 10, 2021
9094189
Give more love to StreamPacketParser
kunaltyagi Jun 12, 2021
fe91951
Fix reference to base class function in `dai::Device`
kunaltyagi Jun 14, 2021
8907017
Add note in the documentation of the virtual functions
kunaltyagi Jun 14, 2021
15ffc7f
Update names, make serialize a public function
kunaltyagi Jun 29, 2021
acd184e
Merge remote-tracking branch 'origin/develop' into feature_tracker
SzabolcsGergely Jul 20, 2021
1f3d09a
Synchronize python-cpp examples
SzabolcsGergely Jul 20, 2021
9cf6976
Merge remote-tracking branch 'origin/develop' into feature_tracker
SzabolcsGergely Jul 21, 2021
70cc8eb
Update FW
SzabolcsGergely Jul 21, 2021
f731586
Add config fields to feature tracker node
SzabolcsGergely Jul 22, 2021
15a35bb
Extend feature tracker configuration
SzabolcsGergely Jul 25, 2021
8d7cd75
Merge remote-tracking branch 'origin/develop' into feature_tracker
SzabolcsGergely Jul 25, 2021
7fc50d1
Add overloaded functions to disable optical flow
SzabolcsGergely Jul 25, 2021
c444db7
Update FW and shared
SzabolcsGergely Jul 26, 2021
a4bc106
Update FW with memory optimizations
SzabolcsGergely Jul 26, 2021
2637a67
Add configurable shave/memory resources to feature tracker
SzabolcsGergely Jul 26, 2021
413449e
Sync python-cpp examples
SzabolcsGergely Jul 26, 2021
44fbe52
Rename FeatureTrackerData to TrackedFeatures
SzabolcsGergely Jul 27, 2021
6ee96e1
Update shared
SzabolcsGergely Jul 27, 2021
2d9aba0
Move startPipeline from DeviceBase to Device
kunaltyagi Jul 28, 2021
a36f090
Make `connection` as protected
kunaltyagi Jul 29, 2021
7250d5e
Add support for hardware accelerated motion estimation
SzabolcsGergely Jul 29, 2021
4fbe284
Shutdown gracefully in case of exception in ctor
kunaltyagi Jul 29, 2021
e197a86
Rename feature tracker config fields
SzabolcsGergely Jul 29, 2021
fba431c
Refactor FeatureTrackerConfig
SzabolcsGergely Jul 29, 2021
48c148f
Merge remote-tracking branch 'origin/develop' into HEAD
SzabolcsGergely Jul 30, 2021
83ad95b
Make ctor API simpler for `DeviceBase` and `Device`
kunaltyagi Jul 30, 2021
6d1e7f0
Keep same behavior in DeviceBase as Device wrt starting pipeline
kunaltyagi Jul 30, 2021
58f023e
Update shared with type fixes in docs; update FW to latest develop
SzabolcsGergely Jul 31, 2021
265b025
Fix docs about feature tracking
SzabolcsGergely Aug 2, 2021
0afa0d5
Rename function arguments to their alias
SzabolcsGergely Aug 2, 2021
0579369
Fix build issue
SzabolcsGergely Aug 2, 2021
3036b2b
Merge branch 'develop' into deviceBase
themarpe Aug 3, 2021
f63bd1f
Handle dtor and close without bugs
kunaltyagi Aug 3, 2021
d53ab26
Fixes for MSVC ambiguity with overloaded constructors
themarpe Aug 5, 2021
ecdec64
Applied style
themarpe Aug 5, 2021
dcbad14
Update FW
SzabolcsGergely Aug 6, 2021
740ee72
Added default constructor as these are not inherited
themarpe Aug 6, 2021
986034e
Merge branch 'main' into develop
themarpe Aug 9, 2021
1a17cbb
Merge remote-tracking branch 'origin/develop' into HEAD
SzabolcsGergely Aug 10, 2021
43c2d15
Merge pull request #181 from luxonis/feature_tracker
SzabolcsGergely Aug 10, 2021
3c56cb5
Add workaround for stereo subpixel/extended mode crash at the expense…
SzabolcsGergely Aug 11, 2021
7b212b9
Merge pull request #196 from luxonis/stereo_crash_workaround
SzabolcsGergely Aug 11, 2021
c807a98
Merge branch 'deviceBase' into develop
themarpe Aug 12, 2021
c33c97a
Merge branch 'main' into develop
themarpe Aug 17, 2021
19deade
Update FW with bilateral fix
SzabolcsGergely Aug 17, 2021
ef5f3fb
Pipeline: add `setXlinkChunkSize`
alex-luxonis Aug 17, 2021
ff58bf0
Fix naming `setXlinkChunkSize` -> `setXLinkChunkSize`
alex-luxonis Aug 18, 2021
0abc44f
DeviceBase/Device: add {set/get}XLinkChunkSize RPC calls
alex-luxonis Aug 23, 2021
a9adca0
Update FW and shared after merge
alex-luxonis Aug 24, 2021
1a6d7da
Merge pull request #199 from luxonis/xlink_chunk_size
alex-luxonis Aug 24, 2021
1f26557
Merge remote-tracking branch 'origin/main' into HEAD
SzabolcsGergely Aug 24, 2021
1204076
Bump version to 2.10.0
SzabolcsGergely Aug 24, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ if(WIN32)
endif()

# Create depthai project
project(depthai VERSION "2.9.0" LANGUAGES CXX C)
project(depthai VERSION "2.10.0" LANGUAGES CXX C)
get_directory_property(has_parent PARENT_DIRECTORY)
if(has_parent)
set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)
Expand Down Expand Up @@ -135,6 +135,7 @@ add_library(${TARGET_CORE_NAME}
"${DEPTHAI_BOOTLOADER_SHARED_SOURCES}"
# sources
src/device/Device.cpp
src/device/DeviceBase.cpp
src/device/DeviceBootloader.cpp
src/device/DataQueue.cpp
src/device/CallbackHandler.cpp
Expand All @@ -160,6 +161,7 @@ add_library(${TARGET_CORE_NAME}
src/pipeline/node/IMU.cpp
src/pipeline/node/EdgeDetector.cpp
src/pipeline/node/SPIIn.cpp
src/pipeline/node/FeatureTracker.cpp
src/pipeline/datatype/Buffer.cpp
src/pipeline/datatype/ImgFrame.cpp
src/pipeline/datatype/ImageManipConfig.cpp
Expand All @@ -168,13 +170,15 @@ add_library(${TARGET_CORE_NAME}
src/pipeline/datatype/ImgDetections.cpp
src/pipeline/datatype/SpatialImgDetections.cpp
src/pipeline/datatype/SystemInformation.cpp
src/pipeline/datatype/StreamPacketParser.cpp
src/pipeline/datatype/StreamMessageParser.cpp
src/pipeline/datatype/SpatialLocationCalculatorData.cpp
src/pipeline/datatype/SpatialLocationCalculatorConfig.cpp
src/pipeline/datatype/Tracklets.cpp
src/pipeline/datatype/IMUData.cpp
src/pipeline/datatype/StereoDepthConfig.cpp
src/pipeline/datatype/EdgeDetectorConfig.cpp
src/pipeline/datatype/TrackedFeatures.cpp
src/pipeline/datatype/FeatureTrackerConfig.cpp
src/utility/Initialization.cpp
src/utility/Resources.cpp
src/xlink/XLinkConnection.cpp
Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceSideConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot")

# "full commit hash of device side binary"
set(DEPTHAI_DEVICE_SIDE_COMMIT "7039346f5bdc77912a9241d3cf5d11b8779ba62e")
set(DEPTHAI_DEVICE_SIDE_COMMIT "1928f3407397272cc9736aedcca667c6c7419057")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
4 changes: 4 additions & 0 deletions examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -271,6 +271,10 @@ dai_add_example(bootloader_version src/bootloader_version.cpp ON)
#dai_add_example(flash_bootloader src/flash_bootloader.cpp OFF)
dai_add_example(edge_detector src/edge_detector.cpp ON)

dai_add_example(feature_tracker src/feature_tracker.cpp ON)

dai_add_example(corner_detector src/corner_detector.cpp ON)

# Calibration Read and write samples
dai_add_example(calibration_flash src/calibration_flash.cpp OFF)
dai_add_example(calibration_flash_version5 src/calibration_flash_v5.cpp OFF)
Expand Down
118 changes: 118 additions & 0 deletions examples/src/corner_detector.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
#include <iostream>

// Inludes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"
#include "deque"
#include "unordered_map"
#include "unordered_set"

static void drawFeatures(cv::Mat& frame, std::vector<dai::TrackedFeature>& features) {
static const auto pointColor = cv::Scalar(0, 0, 255);
static const int circleRadius = 2;
for(auto& feature : features) {
cv::circle(frame, cv::Point(feature.position.x, feature.position.y), circleRadius, pointColor, -1, cv::LINE_AA, 0);
}
}

int main() {
using namespace std;

// Create pipeline
dai::Pipeline pipeline;

// Define sources and outputs
auto monoLeft = pipeline.create<dai::node::MonoCamera>();
auto monoRight = pipeline.create<dai::node::MonoCamera>();
auto featureTrackerLeft = pipeline.create<dai::node::FeatureTracker>();
auto featureTrackerRight = pipeline.create<dai::node::FeatureTracker>();

auto xoutPassthroughFrameLeft = pipeline.create<dai::node::XLinkOut>();
auto xoutTrackedFeaturesLeft = pipeline.create<dai::node::XLinkOut>();
auto xoutPassthroughFrameRight = pipeline.create<dai::node::XLinkOut>();
auto xoutTrackedFeaturesRight = pipeline.create<dai::node::XLinkOut>();
auto xinTrackedFeaturesConfig = pipeline.create<dai::node::XLinkIn>();

xoutPassthroughFrameLeft->setStreamName("passthroughFrameLeft");
xoutTrackedFeaturesLeft->setStreamName("trackedFeaturesLeft");
xoutPassthroughFrameRight->setStreamName("passthroughFrameRight");
xoutTrackedFeaturesRight->setStreamName("trackedFeaturesRight");
xinTrackedFeaturesConfig->setStreamName("trackedFeaturesConfig");

// Properties
monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT);
monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

// Disable optical flow
featureTrackerLeft->initialConfig.setMotionEstimator(false);
featureTrackerRight->initialConfig.setMotionEstimator(false);

// Linking
monoLeft->out.link(featureTrackerLeft->inputImage);
featureTrackerLeft->passthroughInputImage.link(xoutPassthroughFrameLeft->input);
featureTrackerLeft->outputFeatures.link(xoutTrackedFeaturesLeft->input);
xinTrackedFeaturesConfig->out.link(featureTrackerLeft->inputConfig);

monoRight->out.link(featureTrackerRight->inputImage);
featureTrackerRight->passthroughInputImage.link(xoutPassthroughFrameRight->input);
featureTrackerRight->outputFeatures.link(xoutTrackedFeaturesRight->input);
xinTrackedFeaturesConfig->out.link(featureTrackerRight->inputConfig);

auto featureTrackerConfig = featureTrackerRight->initialConfig.get();

printf("Press 's' to switch between Harris and Shi-Thomasi corner detector! \n");

// Connect to device and start pipeline
dai::Device device(pipeline);

// Output queues used to receive the results
auto passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, false);
auto outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, false);
auto passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, false);
auto outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, false);

auto inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig");

const auto leftWindowName = "left";
const auto rightWindowName = "right";

while(true) {
auto inPassthroughFrameLeft = passthroughImageLeftQueue->get<dai::ImgFrame>();
cv::Mat passthroughFrameLeft = inPassthroughFrameLeft->getFrame();
cv::Mat leftFrame;
cv::cvtColor(passthroughFrameLeft, leftFrame, cv::COLOR_GRAY2BGR);

auto inPassthroughFrameRight = passthroughImageRightQueue->get<dai::ImgFrame>();
cv::Mat passthroughFrameRight = inPassthroughFrameRight->getFrame();
cv::Mat rightFrame;
cv::cvtColor(passthroughFrameRight, rightFrame, cv::COLOR_GRAY2BGR);

auto trackedFeaturesLeft = outputFeaturesLeftQueue->get<dai::TrackedFeatures>()->trackedFeatures;
drawFeatures(leftFrame, trackedFeaturesLeft);

auto trackedFeaturesRight = outputFeaturesRightQueue->get<dai::TrackedFeatures>()->trackedFeatures;
drawFeatures(rightFrame, trackedFeaturesRight);

// Show the frame
cv::imshow(leftWindowName, leftFrame);
cv::imshow(rightWindowName, rightFrame);

int key = cv::waitKey(1);
if(key == 'q') {
break;
} else if(key == 's') {
if(featureTrackerConfig.cornerDetector.type == dai::FeatureTrackerConfig::CornerDetector::Type::HARRIS) {
featureTrackerConfig.cornerDetector.type = dai::FeatureTrackerConfig::CornerDetector::Type::SHI_THOMASI;
printf("Switching to Shi-Thomasi \n");
} else {
featureTrackerConfig.cornerDetector.type = dai::FeatureTrackerConfig::CornerDetector::Type::HARRIS;
printf("Switching to Harris \n");
}
auto cfg = dai::FeatureTrackerConfig();
cfg.set(featureTrackerConfig);
inputFeatureTrackerConfigQueue->send(cfg);
}
}
return 0;
}
194 changes: 194 additions & 0 deletions examples/src/feature_tracker.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,194 @@
#include <iostream>

// Inludes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"
#include "deque"
#include "unordered_map"
#include "unordered_set"

static const auto lineColor = cv::Scalar(200, 0, 200);
static const auto pointColor = cv::Scalar(0, 0, 255);

class FeatureTrackerDrawer {
private:
static const int circleRadius = 2;
static const int maxTrackedFeaturesPathLength = 30;
// for how many frames the feature is tracked
static int trackedFeaturesPathLength;

using featureIdType = decltype(dai::Point2f::x);

std::unordered_set<featureIdType> trackedIDs;
std::unordered_map<featureIdType, std::deque<dai::Point2f>> trackedFeaturesPath;

std::string trackbarName;
std::string windowName;

public:
void trackFeaturePath(std::vector<dai::TrackedFeature>& features) {
std::unordered_set<featureIdType> newTrackedIDs;
for(auto& currentFeature : features) {
auto currentID = currentFeature.id;
newTrackedIDs.insert(currentID);

if(!trackedFeaturesPath.count(currentID)) {
trackedFeaturesPath.insert({currentID, std::deque<dai::Point2f>()});
}
std::deque<dai::Point2f>& path = trackedFeaturesPath.at(currentID);

path.push_back(currentFeature.position);
while(path.size() > std::max(1, trackedFeaturesPathLength)) {
path.pop_front();
}
}

std::unordered_set<featureIdType> featuresToRemove;
for(auto& oldId : trackedIDs) {
if(!newTrackedIDs.count(oldId)) {
featuresToRemove.insert(oldId);
}
}

for(auto& id : featuresToRemove) {
trackedFeaturesPath.erase(id);
}

trackedIDs = newTrackedIDs;
}

void drawFeatures(cv::Mat& img) {
cv::setTrackbarPos(trackbarName.c_str(), windowName.c_str(), trackedFeaturesPathLength);

for(auto& featurePath : trackedFeaturesPath) {
std::deque<dai::Point2f>& path = featurePath.second;
int j = 0;
for(j = 0; j < path.size() - 1; j++) {
auto src = cv::Point(path[j].x, path[j].y);
auto dst = cv::Point(path[j + 1].x, path[j + 1].y);
cv::line(img, src, dst, lineColor, 1, cv::LINE_AA, 0);
}

cv::circle(img, cv::Point(path[j].x, path[j].y), circleRadius, pointColor, -1, cv::LINE_AA, 0);
}
}

FeatureTrackerDrawer(std::string trackbarName, std::string windowName) {
this->trackbarName = trackbarName;
this->windowName = windowName;
cv::namedWindow(windowName.c_str());
cv::createTrackbar(trackbarName.c_str(), windowName.c_str(), &trackedFeaturesPathLength, maxTrackedFeaturesPathLength, nullptr);
}
};

int FeatureTrackerDrawer::trackedFeaturesPathLength = 10;

int main() {
using namespace std;

// Create pipeline
dai::Pipeline pipeline;

// Define sources and outputs
auto monoLeft = pipeline.create<dai::node::MonoCamera>();
auto monoRight = pipeline.create<dai::node::MonoCamera>();
auto featureTrackerLeft = pipeline.create<dai::node::FeatureTracker>();
auto featureTrackerRight = pipeline.create<dai::node::FeatureTracker>();

auto xoutPassthroughFrameLeft = pipeline.create<dai::node::XLinkOut>();
auto xoutTrackedFeaturesLeft = pipeline.create<dai::node::XLinkOut>();
auto xoutPassthroughFrameRight = pipeline.create<dai::node::XLinkOut>();
auto xoutTrackedFeaturesRight = pipeline.create<dai::node::XLinkOut>();
auto xinTrackedFeaturesConfig = pipeline.create<dai::node::XLinkIn>();

xoutPassthroughFrameLeft->setStreamName("passthroughFrameLeft");
xoutTrackedFeaturesLeft->setStreamName("trackedFeaturesLeft");
xoutPassthroughFrameRight->setStreamName("passthroughFrameRight");
xoutTrackedFeaturesRight->setStreamName("trackedFeaturesRight");
xinTrackedFeaturesConfig->setStreamName("trackedFeaturesConfig");

// Properties
monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT);
monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P);
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);

// Linking
monoLeft->out.link(featureTrackerLeft->inputImage);
featureTrackerLeft->passthroughInputImage.link(xoutPassthroughFrameLeft->input);
featureTrackerLeft->outputFeatures.link(xoutTrackedFeaturesLeft->input);
xinTrackedFeaturesConfig->out.link(featureTrackerLeft->inputConfig);

monoRight->out.link(featureTrackerRight->inputImage);
featureTrackerRight->passthroughInputImage.link(xoutPassthroughFrameRight->input);
featureTrackerRight->outputFeatures.link(xoutTrackedFeaturesRight->input);
xinTrackedFeaturesConfig->out.link(featureTrackerRight->inputConfig);

// By default the least mount of resources are allocated
// increasing it improves performance when optical flow is enabled
auto numShaves = 2;
auto numMemorySlices = 2;
featureTrackerLeft->setHardwareResources(numShaves, numMemorySlices);
featureTrackerRight->setHardwareResources(numShaves, numMemorySlices);

auto featureTrackerConfig = featureTrackerRight->initialConfig.get();

printf("Press 's' to switch between Lucas-Kanade optical flow and hardware accelerated motion estimation! \n");

// Connect to device and start pipeline
dai::Device device(pipeline);

// Output queues used to receive the results
auto passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, false);
auto outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, false);
auto passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, false);
auto outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, false);

auto inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig");

const auto leftWindowName = "left";
auto leftFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", leftWindowName);

const auto rightWindowName = "right";
auto rightFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", rightWindowName);

while(true) {
auto inPassthroughFrameLeft = passthroughImageLeftQueue->get<dai::ImgFrame>();
cv::Mat passthroughFrameLeft = inPassthroughFrameLeft->getFrame();
cv::Mat leftFrame;
cv::cvtColor(passthroughFrameLeft, leftFrame, cv::COLOR_GRAY2BGR);

auto inPassthroughFrameRight = passthroughImageRightQueue->get<dai::ImgFrame>();
cv::Mat passthroughFrameRight = inPassthroughFrameRight->getFrame();
cv::Mat rightFrame;
cv::cvtColor(passthroughFrameRight, rightFrame, cv::COLOR_GRAY2BGR);

auto trackedFeaturesLeft = outputFeaturesLeftQueue->get<dai::TrackedFeatures>()->trackedFeatures;
leftFeatureDrawer.trackFeaturePath(trackedFeaturesLeft);
leftFeatureDrawer.drawFeatures(leftFrame);

auto trackedFeaturesRight = outputFeaturesRightQueue->get<dai::TrackedFeatures>()->trackedFeatures;
rightFeatureDrawer.trackFeaturePath(trackedFeaturesRight);
rightFeatureDrawer.drawFeatures(rightFrame);

// Show the frame
cv::imshow(leftWindowName, leftFrame);
cv::imshow(rightWindowName, rightFrame);

int key = cv::waitKey(1);
if(key == 'q') {
break;
} else if(key == 's') {
if(featureTrackerConfig.motionEstimator.type == dai::FeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) {
featureTrackerConfig.motionEstimator.type = dai::FeatureTrackerConfig::MotionEstimator::Type::HW_MOTION_ESTIMATION;
printf("Switching to hardware accelerated motion estimation \n");
} else {
featureTrackerConfig.motionEstimator.type = dai::FeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW;
printf("Switching to Lucas-Kanade optical flow \n");
}
auto cfg = dai::FeatureTrackerConfig();
cfg.set(featureTrackerConfig);
inputFeatureTrackerConfigQueue->send(cfg);
}
}
return 0;
}
Loading