From 9b2960727d133d30421fd343d6fe43499fb4fbbd Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 6 Jul 2021 20:20:15 +0300 Subject: [PATCH 01/35] POC: Feature tracker node --- depthai-core | 2 +- examples/feature_tracker.py | 69 +++++++++++++++++++++++++++++++++++++ 2 files changed, 70 insertions(+), 1 deletion(-) create mode 100755 examples/feature_tracker.py diff --git a/depthai-core b/depthai-core index 63ac4f1ae..b4d94058c 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 63ac4f1ae98eae3e77ce7ded0c6a3d6bc7f9fea2 +Subproject commit b4d94058c7b74f3de9332c880c56a82c25c6c3ba diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py new file mode 100755 index 000000000..7ce76c95e --- /dev/null +++ b/examples/feature_tracker.py @@ -0,0 +1,69 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai + +stepSize = 0.05 + +newConfig = False + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +monoLeft = pipeline.createMonoCamera() +monoRight = pipeline.createMonoCamera() +spatialLocationCalculator = pipeline.createSpatialLocationCalculator() + +xoutDepth = pipeline.createXLinkOut() + + +xoutDepth.setStreamName("depth") + + +# Properties +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) + + +# Config +topLeft = dai.Point2f(0.4, 0.4) +bottomRight = dai.Point2f(0.6, 0.6) + +config = dai.SpatialLocationCalculatorConfigData() +config.depthThresholds.lowerThreshold = 100 +config.depthThresholds.upperThreshold = 10000 +config.roi = dai.Rect(topLeft, bottomRight) + +spatialLocationCalculator.setWaitForConfigInput(False) +spatialLocationCalculator.initialConfig.addROI(config) + +# Linking + +spatialLocationCalculator.passthroughDepth.link(xoutDepth.input) +monoLeft.out.link(spatialLocationCalculator.inputDepth) + + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + # Output queue will be used to get the depth frames from the outputs defined above + featureQueue = device.getOutputQueue(name="depth", maxSize=4, blocking=False) + + color = (255, 255, 255) + + print("Use WASD keys to move ROI!") + + while True: + inFeatures = featureQueue.get() # Blocking call, will wait until a new data has arrived + + featureFrame = inFeatures.getFrame() + + # Show the frame + cv2.imshow("features", featureFrame) + + key = cv2.waitKey(1) + if key == ord('q'): + break \ No newline at end of file From 2bd58afa8efac0617fa032f4e64a6b22d2d6d1eb Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 6 Jul 2021 20:47:57 +0300 Subject: [PATCH 02/35] Do tracking on 1280x800 --- examples/feature_tracker.py | 20 +++++--------------- 1 file changed, 5 insertions(+), 15 deletions(-) diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index 7ce76c95e..ddb5a3985 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -3,10 +3,6 @@ import cv2 import depthai as dai -stepSize = 0.05 - -newConfig = False - # Create pipeline pipeline = dai.Pipeline() @@ -18,23 +14,21 @@ xoutDepth = pipeline.createXLinkOut() -xoutDepth.setStreamName("depth") +xoutDepth.setStreamName("features") # Properties -monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P) monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) -monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P) monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) -# Config +# Config, unused topLeft = dai.Point2f(0.4, 0.4) bottomRight = dai.Point2f(0.6, 0.6) config = dai.SpatialLocationCalculatorConfigData() -config.depthThresholds.lowerThreshold = 100 -config.depthThresholds.upperThreshold = 10000 config.roi = dai.Rect(topLeft, bottomRight) spatialLocationCalculator.setWaitForConfigInput(False) @@ -50,11 +44,7 @@ with dai.Device(pipeline) as device: # Output queue will be used to get the depth frames from the outputs defined above - featureQueue = device.getOutputQueue(name="depth", maxSize=4, blocking=False) - - color = (255, 255, 255) - - print("Use WASD keys to move ROI!") + featureQueue = device.getOutputQueue(name="features", maxSize=4, blocking=False) while True: inFeatures = featureQueue.get() # Blocking call, will wait until a new data has arrived From 90fc5c1ffab9fc20370d328550ab566f584802ba Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 9 Jul 2021 06:39:00 +0300 Subject: [PATCH 03/35] Add FeatureDetector node; update example with trajectory --- depthai-core | 2 +- examples/CMakeLists.txt | 1 + examples/feature_tracker.py | 113 +++++++++++++++++++++++------- src/DatatypeBindings.cpp | 48 ++++++++++++- src/pipeline/NodeBindings.cpp | 19 +++++ src/pipeline/PipelineBindings.cpp | 3 + 6 files changed, 158 insertions(+), 28 deletions(-) diff --git a/depthai-core b/depthai-core index b4d94058c..fadbd6895 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit b4d94058c7b74f3de9332c880c56a82c25c6c3ba +Subproject commit fadbd68953a8b12ec19ed83a36c75c647a7082fc diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 86f9e7659..520a644a8 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -126,3 +126,4 @@ add_python_example(imu_gyroscope_accelerometer imu_gyroscope_accelerometer.py) add_python_example(imu_rotation_vector imu_rotation_vector.py) add_python_example(rgb_depth_aligned rgb_depth_aligned.py) add_python_example(edge_detector edge_detector.py) +add_python_example(feature_tracker feature_tracker.py) diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index ddb5a3985..7680c2698 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -2,6 +2,68 @@ import cv2 import depthai as dai +from collections import deque + +trackedIDs = set() +trackedFeaturesPath = dict() + +lineColor = (200, 0, 200) +pointColor = (0, 0, 255) +circleRadius = 2 +maxTrackedFeaturesPathLength = 30 +trackedFeaturesPathLength = 10 + +def onTrackBar(val): + global trackedFeaturesPathLength + trackedFeaturesPathLength = val + pass + +def trackFeaturePath(features): + global trackedIDs + global trackedFeaturesPath + + newTrackedIDs = set() + for currentFeature in features: + currentID = currentFeature.id + newTrackedIDs.add(currentID) + + if currentID not in trackedFeaturesPath: + trackedFeaturesPath[currentID] = deque() + + path = trackedFeaturesPath[currentID] + + path.append(currentFeature.position) + while(len(path) > max(1, trackedFeaturesPathLength)): + path.popleft() + + trackedFeaturesPath[currentID] = path + + featuresToRemove = set() + for oldId in trackedIDs: + if oldId not in newTrackedIDs: + featuresToRemove.add(oldId) + + for id in featuresToRemove: + trackedFeaturesPath.pop(id) + + trackedIDs = newTrackedIDs + +def drawFeatures(img): + global trackedFeaturesPath + + # For every feature, + for featurePath in trackedFeaturesPath.values(): + path = featurePath + + # Draw the feature movement path. + for j in range(len(path) - 1): + src = (int(path[j].x), int(path[j].y)) + dst = (int(path[j + 1].x), int(path[j + 1].y)) + cv2.line(img, src, dst, lineColor, 1, cv2.LINE_AA, 0) + j = len(path) - 1 + cv2.circle(img, (int(path[j].x), int(path[j].y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + + # Create pipeline pipeline = dai.Pipeline() @@ -9,50 +71,49 @@ # Define sources and outputs monoLeft = pipeline.createMonoCamera() monoRight = pipeline.createMonoCamera() -spatialLocationCalculator = pipeline.createSpatialLocationCalculator() +featureTrackerLeft = pipeline.createFeatureTracker() -xoutDepth = pipeline.createXLinkOut() - - -xoutDepth.setStreamName("features") +xoutPassthroughFrameLeft = pipeline.createXLinkOut() +xoutTrackedFeaturesLeft = pipeline.createXLinkOut() +xoutPassthroughFrameLeft.setStreamName("passthroughFrameLeft") +xoutTrackedFeaturesLeft.setStreamName("trackedFeaturesLeft") # Properties -monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P) +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) -monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) - -# Config, unused -topLeft = dai.Point2f(0.4, 0.4) -bottomRight = dai.Point2f(0.6, 0.6) - -config = dai.SpatialLocationCalculatorConfigData() -config.roi = dai.Rect(topLeft, bottomRight) - -spatialLocationCalculator.setWaitForConfigInput(False) -spatialLocationCalculator.initialConfig.addROI(config) - # Linking +monoLeft.out.link(featureTrackerLeft.inputImage) -spatialLocationCalculator.passthroughDepth.link(xoutDepth.input) -monoLeft.out.link(spatialLocationCalculator.inputDepth) - +featureTrackerLeft.passthroughInputImage.link(xoutPassthroughFrameLeft.input) +featureTrackerLeft.outputFeatures.link(xoutTrackedFeaturesLeft.input) # Connect to device and start pipeline with dai.Device(pipeline) as device: - # Output queue will be used to get the depth frames from the outputs defined above - featureQueue = device.getOutputQueue(name="features", maxSize=4, blocking=False) + # Output queues used to receive the results + passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, False) + outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, False) + + leftWindowName = "left" + cv2.namedWindow(leftWindowName) + cv2.createTrackbar("Feature tracking duration (frames)", leftWindowName, trackedFeaturesPathLength, maxTrackedFeaturesPathLength, onTrackBar) while True: - inFeatures = featureQueue.get() # Blocking call, will wait until a new data has arrived + inPassthroughFrameLeft = passthroughImageLeftQueue.get() + + passthroughFrameLeft = inPassthroughFrameLeft.getFrame() + frame = cv2.cvtColor(passthroughFrameLeft, cv2.COLOR_GRAY2BGR) - featureFrame = inFeatures.getFrame() + trackedFeaturesLeft = outputFeaturesLeftQueue.get().trackedFeatures + trackFeaturePath(trackedFeaturesLeft) + drawFeatures(frame) # Show the frame - cv2.imshow("features", featureFrame) + cv2.imshow(leftWindowName, frame) key = cv2.waitKey(1) if key == ord('q'): diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index c939b8f3b..579e52e90 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -20,6 +20,8 @@ #include "depthai/pipeline/datatype/IMUData.hpp" #include "depthai/pipeline/datatype/StereoDepthConfig.hpp" #include "depthai/pipeline/datatype/EdgeDetectorConfig.hpp" +#include "depthai/pipeline/datatype/FeatureTrackerData.hpp" +#include "depthai/pipeline/datatype/FeatureTrackerConfig.hpp" // depthai-shared #include "depthai-shared/datatype/RawBuffer.hpp" @@ -36,7 +38,8 @@ #include "depthai-shared/datatype/RawIMUData.hpp" #include "depthai-shared/datatype/RawStereoDepthConfig.hpp" #include "depthai-shared/datatype/RawEdgeDetectorConfig.hpp" - +#include "depthai-shared/datatype/RawFeatureTrackerConfig.hpp" +#include "depthai-shared/datatype/RawTrackedFeatures.hpp" //pybind #include @@ -893,6 +896,8 @@ void DatatypeBindings::bind(pybind11::module& m){ py::class_>(m, "SpatialLocationCalculatorData", DOC(dai, SpatialLocationCalculatorData)) .def(py::init<>()) .def("getSpatialLocations", &SpatialLocationCalculatorData::getSpatialLocations, DOC(dai, SpatialLocationCalculatorData, getSpatialLocations)) + .def_property("spatialLocations", [](SpatialLocationCalculatorData& loc) { return &loc.spatialLocations; }, [](SpatialLocationCalculatorData& loc, std::vector val) { loc.spatialLocations = val; }, DOC(dai, SpatialLocationCalculatorData, spatialLocations)) + ; // SpatialLocationCalculatorConfig (after ConfigData) @@ -958,4 +963,45 @@ void DatatypeBindings::bind(pybind11::module& m){ .def("getConfigData", &EdgeDetectorConfig::getConfigData, DOC(dai, EdgeDetectorConfig, getConfigData)) ; + // Bind RawTrackedFeatures + py::class_> rawTrackedFeatures(m, "RawTrackedFeatures", DOC(dai, RawTrackedFeatures)); + rawTrackedFeatures + .def(py::init<>()) + .def_readwrite("trackedFeatures", &RawTrackedFeatures::trackedFeatures) + ; + + py::class_ (m, "TrackedFeatures", DOC(dai, TrackedFeatures)) + .def(py::init<>()) + .def_readwrite("position", &TrackedFeatures::position, DOC(dai, TrackedFeatures, position)) + .def_readwrite("id", &TrackedFeatures::id, DOC(dai, TrackedFeatures, id)) + .def_readwrite("age", &TrackedFeatures::age, DOC(dai, TrackedFeatures, age)) + .def_readwrite("harrisScore", &TrackedFeatures::harrisScore, DOC(dai, TrackedFeatures, harrisScore)) + .def_readwrite("trackingError", &TrackedFeatures::trackingError, DOC(dai, TrackedFeatures, trackingError)) + ; + + + // Bind RawTrackedFeatures + py::class_> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); + rawFeatureTrackerConfig + .def(py::init<>()) + .def_readwrite("config", &RawFeatureTrackerConfig::config) + ; + + py::class_ (m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)) + .def(py::init<>()) + .def_readwrite("dummy", &FeatureTrackerConfigData::dummy) + ; + + // Bind FeatureTrackerData + py::class_>(m, "FeatureTrackerData", DOC(dai, FeatureTrackerData)) + .def(py::init<>()) + .def_property("trackedFeatures", [](FeatureTrackerData& feat) { return &feat.trackedFeatures; }, [](FeatureTrackerData& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, FeatureTrackerData, trackedFeatures)) + ; + + // FeatureTrackerConfig (after ConfigData) + py::class_>(m, "FeatureTrackerConfig", DOC(dai, FeatureTrackerConfig)) + .def(py::init<>()) + .def("getConfigData", &FeatureTrackerConfig::getConfigData, DOC(dai, FeatureTrackerConfig, getConfigData)) + ; + } diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index 226006c67..1f0df3eac 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -17,6 +17,7 @@ #include "depthai/pipeline/node/ObjectTracker.hpp" #include "depthai/pipeline/node/IMU.hpp" #include "depthai/pipeline/node/EdgeDetector.hpp" +#include "depthai/pipeline/node/FeatureTracker.hpp" // Libraries #include "hedley/hedley.h" @@ -516,6 +517,16 @@ void NodeBindings::bind(pybind11::module& m){ .def("setMaxOutputFrameSize", &EdgeDetector::setMaxOutputFrameSize, DOC(dai, node, EdgeDetector, setMaxOutputFrameSize)) ; + // FeatureTracker node + py::class_>(m, "FeatureTracker", DOC(dai, node, FeatureTracker)) + .def_readonly("inputConfig", &FeatureTracker::inputConfig, DOC(dai, node, FeatureTracker, inputConfig)) + .def_readonly("inputImage", &FeatureTracker::inputImage, DOC(dai, node, FeatureTracker, inputImage)) + .def_readonly("outputFeatures", &FeatureTracker::outputFeatures, DOC(dai, node, FeatureTracker, outputFeatures)) + .def_readonly("passthroughInputImage", &FeatureTracker::passthroughInputImage, DOC(dai, node, FeatureTracker, passthroughInputImage)) + .def_readonly("initialConfig", &FeatureTracker::initialConfig, DOC(dai, node, FeatureTracker, initialConfig)) + .def("setWaitForConfigInput", &FeatureTracker::setWaitForConfigInput, py::arg("wait"), DOC(dai, node, FeatureTracker, setWaitForConfigInput)) + ; + //////////////////////////////////// // Node properties bindings //////////////////////////////////// @@ -770,5 +781,13 @@ void NodeBindings::bind(pybind11::module& m){ m.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; + py::class_ featureTrackerProperties(m, "FeatureTrackerProperties", DOC(dai, FeatureTrackerProperties)); + featureTrackerProperties + .def_readwrite("initialConfig", &FeatureTrackerProperties::initialConfig, DOC(dai, FeatureTrackerProperties, initialConfig)) + .def_readwrite("inputConfigSync", &FeatureTrackerProperties::inputConfigSync, DOC(dai, FeatureTrackerProperties, inputConfigSync)) + ; + m.attr("SpatialLocationCalculator").attr("Properties") = featureTrackerProperties; + + } diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 193f762b4..9096f6e8a 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -20,6 +20,7 @@ #include "depthai/pipeline/node/ObjectTracker.hpp" #include "depthai/pipeline/node/IMU.hpp" #include "depthai/pipeline/node/EdgeDetector.hpp" +#include "depthai/pipeline/node/FeatureTracker.hpp" // depthai-shared #include "depthai-shared/properties/GlobalProperties.hpp" @@ -82,6 +83,8 @@ void PipelineBindings::bind(pybind11::module& m){ .def("createObjectTracker", &Pipeline::create) .def("createIMU", &Pipeline::create) .def("createEdgeDetector", &Pipeline::create) + .def("createFeatureTracker", &Pipeline::create) + ; From 24c361bf4c07ef43c298042e75279964aa6ab97c Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 20 Jul 2021 04:26:51 +0300 Subject: [PATCH 04/35] Feature tracking on stereo frames --- examples/feature_tracker.py | 127 +++++++++++++++++++++--------------- 1 file changed, 75 insertions(+), 52 deletions(-) diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index 7680c2698..60d1d8b9b 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -4,65 +4,68 @@ import depthai as dai from collections import deque -trackedIDs = set() -trackedFeaturesPath = dict() +class FeatureTrackerDrawer: -lineColor = (200, 0, 200) -pointColor = (0, 0, 255) -circleRadius = 2 -maxTrackedFeaturesPathLength = 30 -trackedFeaturesPathLength = 10 + trackedIDs = None + trackedFeaturesPath = None -def onTrackBar(val): - global trackedFeaturesPathLength - trackedFeaturesPathLength = val - pass + lineColor = (200, 0, 200) + pointColor = (0, 0, 255) + circleRadius = 2 + maxTrackedFeaturesPathLength = 30 + trackedFeaturesPathLength = 10 -def trackFeaturePath(features): - global trackedIDs - global trackedFeaturesPath + def onTrackBar(self, val): + self.trackedFeaturesPathLength = val + pass - newTrackedIDs = set() - for currentFeature in features: - currentID = currentFeature.id - newTrackedIDs.add(currentID) + def trackFeaturePath(self, features): - if currentID not in trackedFeaturesPath: - trackedFeaturesPath[currentID] = deque() + newTrackedIDs = set() + for currentFeature in features: + currentID = currentFeature.id + newTrackedIDs.add(currentID) - path = trackedFeaturesPath[currentID] + if currentID not in self.trackedFeaturesPath: + self.trackedFeaturesPath[currentID] = deque() - path.append(currentFeature.position) - while(len(path) > max(1, trackedFeaturesPathLength)): - path.popleft() + path = self.trackedFeaturesPath[currentID] - trackedFeaturesPath[currentID] = path + path.append(currentFeature.position) + while(len(path) > max(1, self.trackedFeaturesPathLength)): + path.popleft() - featuresToRemove = set() - for oldId in trackedIDs: - if oldId not in newTrackedIDs: - featuresToRemove.add(oldId) + self.trackedFeaturesPath[currentID] = path - for id in featuresToRemove: - trackedFeaturesPath.pop(id) + featuresToRemove = set() + for oldId in self.trackedIDs: + if oldId not in newTrackedIDs: + featuresToRemove.add(oldId) - trackedIDs = newTrackedIDs + for id in featuresToRemove: + self.trackedFeaturesPath.pop(id) -def drawFeatures(img): - global trackedFeaturesPath + self.trackedIDs = newTrackedIDs - # For every feature, - for featurePath in trackedFeaturesPath.values(): - path = featurePath + def drawFeatures(self, img): - # Draw the feature movement path. - for j in range(len(path) - 1): - src = (int(path[j].x), int(path[j].y)) - dst = (int(path[j + 1].x), int(path[j + 1].y)) - cv2.line(img, src, dst, lineColor, 1, cv2.LINE_AA, 0) - j = len(path) - 1 - cv2.circle(img, (int(path[j].x), int(path[j].y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + # For every feature, + for featurePath in self.trackedFeaturesPath.values(): + path = featurePath + # Draw the feature movement path. + for j in range(len(path) - 1): + src = (int(path[j].x), int(path[j].y)) + dst = (int(path[j + 1].x), int(path[j + 1].y)) + cv2.line(img, src, dst, self.lineColor, 1, cv2.LINE_AA, 0) + j = len(path) - 1 + cv2.circle(img, (int(path[j].x), int(path[j].y)), self.circleRadius, self.pointColor, -1, cv2.LINE_AA, 0) + + def __init__(self, trackbarName, windowName): + cv2.namedWindow(windowName) + cv2.createTrackbar(trackbarName, windowName, self.trackedFeaturesPathLength, self.maxTrackedFeaturesPathLength, self.onTrackBar) + self.trackedIDs = set() + self.trackedFeaturesPath = dict() # Create pipeline @@ -72,12 +75,17 @@ def drawFeatures(img): monoLeft = pipeline.createMonoCamera() monoRight = pipeline.createMonoCamera() featureTrackerLeft = pipeline.createFeatureTracker() +featureTrackerRight = pipeline.createFeatureTracker() xoutPassthroughFrameLeft = pipeline.createXLinkOut() xoutTrackedFeaturesLeft = pipeline.createXLinkOut() +xoutPassthroughFrameRight = pipeline.createXLinkOut() +xoutTrackedFeaturesRight = pipeline.createXLinkOut() xoutPassthroughFrameLeft.setStreamName("passthroughFrameLeft") xoutTrackedFeaturesLeft.setStreamName("trackedFeaturesLeft") +xoutPassthroughFrameRight.setStreamName("passthroughFrameRight") +xoutTrackedFeaturesRight.setStreamName("trackedFeaturesRight") # Properties monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) @@ -87,33 +95,48 @@ def drawFeatures(img): # Linking monoLeft.out.link(featureTrackerLeft.inputImage) - featureTrackerLeft.passthroughInputImage.link(xoutPassthroughFrameLeft.input) featureTrackerLeft.outputFeatures.link(xoutTrackedFeaturesLeft.input) +monoRight.out.link(featureTrackerRight.inputImage) +featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) +featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) + # Connect to device and start pipeline with dai.Device(pipeline) as device: # Output queues used to receive the results passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, False) outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, False) + passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, False) + outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, False) leftWindowName = "left" - cv2.namedWindow(leftWindowName) - cv2.createTrackbar("Feature tracking duration (frames)", leftWindowName, trackedFeaturesPathLength, maxTrackedFeaturesPathLength, onTrackBar) + leftFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", leftWindowName) + + rightWindowName = "right" + rightFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", rightWindowName) while True: inPassthroughFrameLeft = passthroughImageLeftQueue.get() - passthroughFrameLeft = inPassthroughFrameLeft.getFrame() - frame = cv2.cvtColor(passthroughFrameLeft, cv2.COLOR_GRAY2BGR) + leftFrame = cv2.cvtColor(passthroughFrameLeft, cv2.COLOR_GRAY2BGR) + + inPassthroughFrameRight = passthroughImageRightQueue.get() + passthroughFrameRight = inPassthroughFrameRight.getFrame() + rightFrame = cv2.cvtColor(passthroughFrameRight, cv2.COLOR_GRAY2BGR) trackedFeaturesLeft = outputFeaturesLeftQueue.get().trackedFeatures - trackFeaturePath(trackedFeaturesLeft) - drawFeatures(frame) + leftFeatureDrawer.trackFeaturePath(trackedFeaturesLeft) + leftFeatureDrawer.drawFeatures(leftFrame) + + trackedFeaturesRight = outputFeaturesRightQueue.get().trackedFeatures + rightFeatureDrawer.trackFeaturePath(trackedFeaturesRight) + rightFeatureDrawer.drawFeatures(rightFrame) # Show the frame - cv2.imshow(leftWindowName, frame) + cv2.imshow(leftWindowName, leftFrame) + cv2.imshow(rightWindowName, rightFrame) key = cv2.waitKey(1) if key == ord('q'): From e834ab47b65d0606a9c0b0b36fbd13b01cbb3c62 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Thu, 22 Jul 2021 11:41:58 +0300 Subject: [PATCH 05/35] Add config fields to feature tracker node --- depthai-core | 2 +- src/DatatypeBindings.cpp | 20 ++++++++++++++++++-- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/depthai-core b/depthai-core index 70cc8eb42..f7315861a 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 70cc8eb42a21d337b0341941719a21a892a14062 +Subproject commit f7315861a8a53f0c40092e8a57a8cb91a7261687 diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index ca2464d09..4bd6775ee 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -987,9 +987,22 @@ void DatatypeBindings::bind(pybind11::module& m){ .def_readwrite("config", &RawFeatureTrackerConfig::config) ; - py::class_ (m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)) + py::class_ featureTrackerConfigData(m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)); + featureTrackerConfigData .def(py::init<>()) - .def_readwrite("dummy", &FeatureTrackerConfigData::dummy) + .def_readwrite("algorithmType", &FeatureTrackerConfigData::algorithmType, DOC(dai, FeatureTrackerConfigData, algorithmType)) + .def_readwrite("cornerDetector", &FeatureTrackerConfigData::cornerDetector, DOC(dai, FeatureTrackerConfigData, cornerDetector)) + .def_readwrite("targetNrFeatures", &FeatureTrackerConfigData::targetNrFeatures, DOC(dai, FeatureTrackerConfigData, targetNrFeatures)) + ; + + py::enum_(featureTrackerConfigData, "AlgorithmType") + .value("CORNER_DETECTION", FeatureTrackerConfigData::AlgorithmType::CORNER_DETECTION) + .value("CORNER_DETECTION_WITH_OPTICAL_FLOW", FeatureTrackerConfigData::AlgorithmType::CORNER_DETECTION_WITH_OPTICAL_FLOW) + ; + + py::enum_(featureTrackerConfigData, "CornerDetector") + .value("HARRIS", FeatureTrackerConfigData::CornerDetector::HARRIS) + .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::SHI_THOMASI) ; // Bind FeatureTrackerData @@ -1001,6 +1014,9 @@ void DatatypeBindings::bind(pybind11::module& m){ // FeatureTrackerConfig (after ConfigData) py::class_>(m, "FeatureTrackerConfig", DOC(dai, FeatureTrackerConfig)) .def(py::init<>()) + .def("setAlgorithmType", &FeatureTrackerConfig::setAlgorithmType, DOC(dai, FeatureTrackerConfig, setAlgorithmType)) + .def("setCornerDetector", &FeatureTrackerConfig::setCornerDetector, DOC(dai, FeatureTrackerConfig, setCornerDetector)) + .def("setTargetNrFeatures", &FeatureTrackerConfig::setTargetNrFeatures, DOC(dai, FeatureTrackerConfig, setTargetNrFeatures)) .def("getConfigData", &FeatureTrackerConfig::getConfigData, DOC(dai, FeatureTrackerConfig, getConfigData)) ; From 57c284c2dbcc498254ef52b97cae2c274c3fafe4 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sun, 25 Jul 2021 13:17:15 +0300 Subject: [PATCH 06/35] Add bindings for feature tracker --- depthai-core | 2 +- src/DatatypeBindings.cpp | 109 ++++++++++++++++++++++++++-------- src/pipeline/NodeBindings.cpp | 23 +++---- 3 files changed, 99 insertions(+), 35 deletions(-) diff --git a/depthai-core b/depthai-core index f7315861a..8d7cd7558 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit f7315861a8a53f0c40092e8a57a8cb91a7261687 +Subproject commit 8d7cd755878e3556b82e8975111efb56dcf93091 diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 7d07a3501..42693a49f 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -110,6 +110,20 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ py::class_ edgeDetectorConfigData(m, "EdgeDetectorConfigData", DOC(dai, EdgeDetectorConfigData)); py::class_> rawEdgeDetectorConfig(m, "RawEdgeDetectorConfig", DOC(dai, RawEdgeDetectorConfig)); py::class_> edgeDetectorConfig(m, "EdgeDetectorConfig", DOC(dai, EdgeDetectorConfig)); + // Feature tracker + py::class_> rawTrackedFeatures(m, "RawTrackedFeatures", DOC(dai, RawTrackedFeatures)); + py::class_ trackedFeature(m, "TrackedFeature", DOC(dai, TrackedFeature)); + py::class_> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); + py::class_ featureTrackerConfigData(m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)); + py::class_ cornerDetector(featureTrackerConfigData, "CornerDetector", DOC(dai, FeatureTrackerConfigData, CornerDetector)); + py::enum_ cornerDetectorType(cornerDetector, "AlgorithmType", DOC(dai, FeatureTrackerConfigData, CornerDetector, AlgorithmType)); + py::class_ cornerDetectorThresholds(cornerDetector, "Thresholds", DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds)); + py::class_ motionEstimator(featureTrackerConfigData, "MotionEstimator", DOC(dai, FeatureTrackerConfigData, MotionEstimator)); + py::enum_ motionEstimatorType(motionEstimator, "AlgorithmType", DOC(dai, FeatureTrackerConfigData, MotionEstimator, AlgorithmType)); + py::class_ motionEstimatorOpticalFlow(motionEstimator, "OpticalFlow", DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow)); + + py::class_ featureMaintainer(featureTrackerConfigData, "FeatureMaintainer", DOC(dai, FeatureTrackerConfigData, FeatureMaintainer)); + py::class_> featureTrackerConfig(m, "FeatureTrackerConfig", DOC(dai, FeatureTrackerConfig)); /////////////////////////////////////////////////////////////////////// @@ -1048,60 +1062,107 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ ; // Bind RawTrackedFeatures - py::class_> rawTrackedFeatures(m, "RawTrackedFeatures", DOC(dai, RawTrackedFeatures)); rawTrackedFeatures .def(py::init<>()) .def_readwrite("trackedFeatures", &RawTrackedFeatures::trackedFeatures) ; - py::class_ (m, "TrackedFeatures", DOC(dai, TrackedFeatures)) + trackedFeature .def(py::init<>()) - .def_readwrite("position", &TrackedFeatures::position, DOC(dai, TrackedFeatures, position)) - .def_readwrite("id", &TrackedFeatures::id, DOC(dai, TrackedFeatures, id)) - .def_readwrite("age", &TrackedFeatures::age, DOC(dai, TrackedFeatures, age)) - .def_readwrite("harrisScore", &TrackedFeatures::harrisScore, DOC(dai, TrackedFeatures, harrisScore)) - .def_readwrite("trackingError", &TrackedFeatures::trackingError, DOC(dai, TrackedFeatures, trackingError)) + .def_readwrite("position", &TrackedFeature::position, DOC(dai, TrackedFeature, position)) + .def_readwrite("id", &TrackedFeature::id, DOC(dai, TrackedFeature, id)) +#if 0 + .def_readwrite("age", &TrackedFeature::age, DOC(dai, TrackedFeature, age)) + .def_readwrite("harrisScore", &TrackedFeature::harrisScore, DOC(dai, TrackedFeature, harrisScore)) + .def_readwrite("trackingError", &TrackedFeature::trackingError, DOC(dai, TrackedFeature, trackingError)) +#endif ; - // Bind RawTrackedFeatures - py::class_> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); rawFeatureTrackerConfig .def(py::init<>()) .def_readwrite("config", &RawFeatureTrackerConfig::config) ; - py::class_ featureTrackerConfigData(m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)); featureTrackerConfigData .def(py::init<>()) - .def_readwrite("algorithmType", &FeatureTrackerConfigData::algorithmType, DOC(dai, FeatureTrackerConfigData, algorithmType)) .def_readwrite("cornerDetector", &FeatureTrackerConfigData::cornerDetector, DOC(dai, FeatureTrackerConfigData, cornerDetector)) - .def_readwrite("targetNrFeatures", &FeatureTrackerConfigData::targetNrFeatures, DOC(dai, FeatureTrackerConfigData, targetNrFeatures)) + .def_readwrite("motionEstimator", &FeatureTrackerConfigData::motionEstimator, DOC(dai, FeatureTrackerConfigData, motionEstimator)) + .def_readwrite("featureMaintainer", &FeatureTrackerConfigData::featureMaintainer, DOC(dai, FeatureTrackerConfigData, featureMaintainer)) + ; + + cornerDetectorType + .value("HARRIS", FeatureTrackerConfigData::CornerDetector::AlgorithmType::HARRIS) + .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::AlgorithmType::SHI_THOMASI) + ; + + cornerDetectorThresholds + .def(py::init<>()) + .def_readwrite("initialValue", &FeatureTrackerConfigData::CornerDetector::Thresholds::initialValue, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, initialValue)) + .def_readwrite("min", &FeatureTrackerConfigData::CornerDetector::Thresholds::min, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, min)) + .def_readwrite("max", &FeatureTrackerConfigData::CornerDetector::Thresholds::max, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, max)) + .def_readwrite("decreaseFactor", &FeatureTrackerConfigData::CornerDetector::Thresholds::decreaseFactor, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, decreaseFactor)) + .def_readwrite("increaseFactor", &FeatureTrackerConfigData::CornerDetector::Thresholds::increaseFactor, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, increaseFactor)) ; - py::enum_(featureTrackerConfigData, "AlgorithmType") - .value("CORNER_DETECTION", FeatureTrackerConfigData::AlgorithmType::CORNER_DETECTION) - .value("CORNER_DETECTION_WITH_OPTICAL_FLOW", FeatureTrackerConfigData::AlgorithmType::CORNER_DETECTION_WITH_OPTICAL_FLOW) + cornerDetector + .def(py::init<>()) + .def_readwrite("algorithmType", &FeatureTrackerConfigData::CornerDetector::algorithmType, DOC(dai, FeatureTrackerConfigData, CornerDetector, algorithmType)) + .def_readwrite("numImageCells", &FeatureTrackerConfigData::CornerDetector::numImageCells, DOC(dai, FeatureTrackerConfigData, CornerDetector, numImageCells)) + .def_readwrite("targetNumFeatures", &FeatureTrackerConfigData::CornerDetector::targetNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, targetNumFeatures)) + .def_readwrite("maxNumFeatures", &FeatureTrackerConfigData::CornerDetector::maxNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, maxNumFeatures)) + .def_readwrite("enableSobel", &FeatureTrackerConfigData::CornerDetector::enableSobel, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSobel)) + .def_readwrite("enableSorting", &FeatureTrackerConfigData::CornerDetector::enableSorting, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSorting)) + .def_readwrite("thresholds", &FeatureTrackerConfigData::CornerDetector::thresholds, DOC(dai, FeatureTrackerConfigData, CornerDetector, thresholds)) ; - py::enum_(featureTrackerConfigData, "CornerDetector") - .value("HARRIS", FeatureTrackerConfigData::CornerDetector::HARRIS) - .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::SHI_THOMASI) + motionEstimatorType + .value("LUCAS_KANADE_OPTICAL_FLOW", FeatureTrackerConfigData::MotionEstimator::AlgorithmType::LUCAS_KANADE_OPTICAL_FLOW) + ; + + motionEstimatorOpticalFlow + .def(py::init<>()) + .def_readwrite("pyramidLevels", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::pyramidLevels, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, pyramidLevels)) + .def_readwrite("searchWindowWidth", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::searchWindowWidth, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, searchWindowWidth)) + .def_readwrite("searchWindowHeight", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::searchWindowHeight, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, searchWindowHeight)) + .def_readwrite("epsilon", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::epsilon, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, epsilon)) + .def_readwrite("maxIterations", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::maxIterations, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, maxIterations)) ; + motionEstimator + .def(py::init<>()) + .def_readwrite("enable", &FeatureTrackerConfigData::MotionEstimator::enable, DOC(dai, FeatureTrackerConfigData, MotionEstimator, enable)) + .def_readwrite("algorithmType", &FeatureTrackerConfigData::MotionEstimator::algorithmType, DOC(dai, FeatureTrackerConfigData, MotionEstimator, algorithmType)) + .def_readwrite("opticalFlow", &FeatureTrackerConfigData::MotionEstimator::opticalFlow, DOC(dai, FeatureTrackerConfigData, MotionEstimator, opticalFlow)) + ; + + featureMaintainer + .def(py::init<>()) + .def_readwrite("enable", &FeatureTrackerConfigData::FeatureMaintainer::enable, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, enable)) + .def_readwrite("minimumDistanceBetweenFeatures", &FeatureTrackerConfigData::FeatureMaintainer::minimumDistanceBetweenFeatures, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, minimumDistanceBetweenFeatures)) + .def_readwrite("lostFeatureErrorThreshold", &FeatureTrackerConfigData::FeatureMaintainer::lostFeatureErrorThreshold, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, lostFeatureErrorThreshold)) + .def_readwrite("trackedFeatureThreshold", &FeatureTrackerConfigData::FeatureMaintainer::trackedFeatureThreshold, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, trackedFeatureThreshold)) + ; + + // Bind FeatureTrackerData py::class_>(m, "FeatureTrackerData", DOC(dai, FeatureTrackerData)) .def(py::init<>()) - .def_property("trackedFeatures", [](FeatureTrackerData& feat) { return &feat.trackedFeatures; }, [](FeatureTrackerData& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, FeatureTrackerData, trackedFeatures)) + .def_property("trackedFeatures", [](FeatureTrackerData& feat) { return &feat.trackedFeatures; }, [](FeatureTrackerData& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, FeatureTrackerData, trackedFeatures)) ; // FeatureTrackerConfig (after ConfigData) - py::class_>(m, "FeatureTrackerConfig", DOC(dai, FeatureTrackerConfig)) + featureTrackerConfig .def(py::init<>()) - .def("setAlgorithmType", &FeatureTrackerConfig::setAlgorithmType, DOC(dai, FeatureTrackerConfig, setAlgorithmType)) - .def("setCornerDetector", &FeatureTrackerConfig::setCornerDetector, DOC(dai, FeatureTrackerConfig, setCornerDetector)) - .def("setTargetNrFeatures", &FeatureTrackerConfig::setTargetNrFeatures, DOC(dai, FeatureTrackerConfig, setTargetNrFeatures)) - .def("getConfigData", &FeatureTrackerConfig::getConfigData, DOC(dai, FeatureTrackerConfig, getConfigData)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) + + .def("setOpticalFlow", &FeatureTrackerConfig::setOpticalFlow, py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) + .def("setTargetNumFeatures", &FeatureTrackerConfig::setTargetNumFeatures, py::arg("targetNumFeatures"), DOC(dai, FeatureTrackerConfig, setTargetNumFeatures)) + .def("setMotionEstimator", &FeatureTrackerConfig::setMotionEstimator, py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) + .def("setFeatureMaintainer", &FeatureTrackerConfig::setFeatureMaintainer, py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) + .def("set", &FeatureTrackerConfig::set, py::arg("config"), DOC(dai, FeatureTrackerConfig, set)) + .def("get", &FeatureTrackerConfig::get, DOC(dai, FeatureTrackerConfig, get)) ; } diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index fe30daab9..0c86cd6c8 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -174,6 +174,7 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ py::class_ edgeDetectorProperties(m, "EdgeDetectorProperties", DOC(dai, EdgeDetectorProperties)); py::class_ spiOutProperties(m, "SPIOutProperties", DOC(dai, SPIOutProperties)); py::class_ spiInProperties(m, "SPIInProperties", DOC(dai, SPIInProperties)); + py::class_ featureTrackerProperties(m, "FeatureTrackerProperties", DOC(dai, FeatureTrackerProperties)); py::class_> pyNode(m, "Node", DOC(dai, Node)); py::class_ pyInput(pyNode, "Input", DOC(dai, Node, Input)); py::enum_ nodeInputType(pyInput, "Type"); @@ -209,6 +210,7 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ auto script = ADD_NODE(Script); auto imu = ADD_NODE(IMU); auto edgeDetector = ADD_NODE(EdgeDetector); + auto featureTracker = ADD_NODE(FeatureTracker); @@ -453,6 +455,12 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ .def_readwrite("numFrames", &SPIInProperties::numFrames) ; + // FeatureTracker properties + featureTrackerProperties + .def_readwrite("initialConfig", &FeatureTrackerProperties::initialConfig, DOC(dai, FeatureTrackerProperties, initialConfig)) + .def_readwrite("inputConfigSync", &FeatureTrackerProperties::inputConfigSync, DOC(dai, FeatureTrackerProperties, inputConfigSync)) + ; + //////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////// @@ -1013,8 +1021,11 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ .def("setNumFramesPool", &EdgeDetector::setNumFramesPool, DOC(dai, node, EdgeDetector, setNumFramesPool)) .def("setMaxOutputFrameSize", &EdgeDetector::setMaxOutputFrameSize, DOC(dai, node, EdgeDetector, setMaxOutputFrameSize)) ; + daiNodeModule.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; + + // FeatureTracker node - py::class_>(m, "FeatureTracker", DOC(dai, node, FeatureTracker)) + featureTracker .def_readonly("inputConfig", &FeatureTracker::inputConfig, DOC(dai, node, FeatureTracker, inputConfig)) .def_readonly("inputImage", &FeatureTracker::inputImage, DOC(dai, node, FeatureTracker, inputImage)) .def_readonly("outputFeatures", &FeatureTracker::outputFeatures, DOC(dai, node, FeatureTracker, outputFeatures)) @@ -1022,15 +1033,7 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ .def_readonly("initialConfig", &FeatureTracker::initialConfig, DOC(dai, node, FeatureTracker, initialConfig)) .def("setWaitForConfigInput", &FeatureTracker::setWaitForConfigInput, py::arg("wait"), DOC(dai, node, FeatureTracker, setWaitForConfigInput)) ; - daiNodeModule.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; - - - py::class_ featureTrackerProperties(m, "FeatureTrackerProperties", DOC(dai, FeatureTrackerProperties)); - featureTrackerProperties - .def_readwrite("initialConfig", &FeatureTrackerProperties::initialConfig, DOC(dai, FeatureTrackerProperties, initialConfig)) - .def_readwrite("inputConfigSync", &FeatureTrackerProperties::inputConfigSync, DOC(dai, FeatureTrackerProperties, inputConfigSync)) - ; - m.attr("SpatialLocationCalculator").attr("Properties") = featureTrackerProperties; + daiNodeModule.attr("FeatureTracker").attr("Properties") = featureTrackerProperties; } From 5e94ecab43c6bb6379fb65adf6407865fba7179e Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sun, 25 Jul 2021 13:35:02 +0300 Subject: [PATCH 07/35] Add overloaded functions to disable optical flow --- depthai-core | 2 +- src/DatatypeBindings.cpp | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/depthai-core b/depthai-core index 8d7cd7558..7fc50d16f 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 8d7cd755878e3556b82e8975111efb56dcf93091 +Subproject commit 7fc50d16fe2623582dad159d81c686fdb1fc0b9b diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 42693a49f..bc65fec3b 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -1156,11 +1156,13 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def(py::init<>()) .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) - + .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) + .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) .def("setOpticalFlow", &FeatureTrackerConfig::setOpticalFlow, py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) + .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) + .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) .def("setTargetNumFeatures", &FeatureTrackerConfig::setTargetNumFeatures, py::arg("targetNumFeatures"), DOC(dai, FeatureTrackerConfig, setTargetNumFeatures)) - .def("setMotionEstimator", &FeatureTrackerConfig::setMotionEstimator, py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) - .def("setFeatureMaintainer", &FeatureTrackerConfig::setFeatureMaintainer, py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) + .def("set", &FeatureTrackerConfig::set, py::arg("config"), DOC(dai, FeatureTrackerConfig, set)) .def("get", &FeatureTrackerConfig::get, DOC(dai, FeatureTrackerConfig, get)) ; From feca58b9972a3ce084d615d003f10f193c638d1e Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sun, 25 Jul 2021 14:20:16 +0300 Subject: [PATCH 08/35] Add corner detector example: Harris or Shi-Thomasi --- examples/corner_detector.py | 107 ++++++++++++++++++++++++++++++++++++ 1 file changed, 107 insertions(+) create mode 100755 examples/corner_detector.py diff --git a/examples/corner_detector.py b/examples/corner_detector.py new file mode 100755 index 000000000..47f01204c --- /dev/null +++ b/examples/corner_detector.py @@ -0,0 +1,107 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai + + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +monoLeft = pipeline.createMonoCamera() +monoRight = pipeline.createMonoCamera() +featureTrackerLeft = pipeline.createFeatureTracker() +featureTrackerRight = pipeline.createFeatureTracker() + +xoutPassthroughFrameLeft = pipeline.createXLinkOut() +xoutTrackedFeaturesLeft = pipeline.createXLinkOut() +xoutPassthroughFrameRight = pipeline.createXLinkOut() +xoutTrackedFeaturesRight = pipeline.createXLinkOut() +xinTrackedFeaturesConfig = pipeline.createXLinkIn() + + +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) +featureTrackerLeft.initialConfig.setMotionEstimator(False) +xinTrackedFeaturesConfig.out.link(featureTrackerLeft.inputConfig) + +monoRight.out.link(featureTrackerRight.inputImage) +featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) +featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) +featureTrackerRight.initialConfig.setMotionEstimator(False) +xinTrackedFeaturesConfig.out.link(featureTrackerRight.inputConfig) + +featureTrackerConfig = featureTrackerRight.initialConfig.get() + +print("Press 's' to switch between Harris and Shi-Thomasi corner detector!") + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + # Output queues used to receive the results + passthroughImageLeftQueue = device.getOutputQueue("passthroughFrameLeft", 8, False) + outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, False) + passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, False) + outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, False) + + inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig") + + + leftWindowName = "left" + rightWindowName = "right" + + pointColor = (0, 0, 255) + circleRadius = 2 + + while True: + inPassthroughFrameLeft = passthroughImageLeftQueue.get() + passthroughFrameLeft = inPassthroughFrameLeft.getFrame() + leftFrame = cv2.cvtColor(passthroughFrameLeft, cv2.COLOR_GRAY2BGR) + + inPassthroughFrameRight = passthroughImageRightQueue.get() + passthroughFrameRight = inPassthroughFrameRight.getFrame() + rightFrame = cv2.cvtColor(passthroughFrameRight, cv2.COLOR_GRAY2BGR) + + trackedFeaturesLeft = outputFeaturesLeftQueue.get().trackedFeatures + for feature in trackedFeaturesLeft: + cv2.circle(leftFrame, (int(feature.position.x), int(feature.position.y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + + trackedFeaturesRight = outputFeaturesRightQueue.get().trackedFeatures + for feature in trackedFeaturesRight: + cv2.circle(rightFrame, (int(feature.position.x), int(feature.position.y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + + # Show the frame + cv2.imshow(leftWindowName, leftFrame) + cv2.imshow(rightWindowName, rightFrame) + + key = cv2.waitKey(1) + if key == ord('q'): + break + elif key == ord('s'): + if featureTrackerConfig.cornerDetector.algorithmType == dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS: + featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.SHI_THOMASI + print("Switchig to Shi-Thomasi") + else: + featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS + print("Switchig to Harris") + + cfg = dai.FeatureTrackerConfig() + cfg.set(featureTrackerConfig) + inputFeatureTrackerConfigQueue.send(cfg) + + + pass \ No newline at end of file From f18ab423c588370b48d2cb281b07bb005dbe3d6c Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 26 Jul 2021 12:24:26 +0300 Subject: [PATCH 09/35] Add configurable shave/memory resources to feature tracker --- depthai-core | 2 +- src/DatatypeBindings.cpp | 4 +++- src/pipeline/NodeBindings.cpp | 1 + 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index 7fc50d16f..2637a674f 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 7fc50d16fe2623582dad159d81c686fdb1fc0b9b +Subproject commit 2637a674f0d2b2ced640bda1b07c1afc5cd44e43 diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index bc65fec3b..72b81eaa5 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -1108,7 +1108,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ cornerDetector .def(py::init<>()) .def_readwrite("algorithmType", &FeatureTrackerConfigData::CornerDetector::algorithmType, DOC(dai, FeatureTrackerConfigData, CornerDetector, algorithmType)) - .def_readwrite("numImageCells", &FeatureTrackerConfigData::CornerDetector::numImageCells, DOC(dai, FeatureTrackerConfigData, CornerDetector, numImageCells)) + .def_readwrite("cellGridDimension", &FeatureTrackerConfigData::CornerDetector::cellGridDimension, DOC(dai, FeatureTrackerConfigData, CornerDetector, cellGridDimension)) .def_readwrite("targetNumFeatures", &FeatureTrackerConfigData::CornerDetector::targetNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, targetNumFeatures)) .def_readwrite("maxNumFeatures", &FeatureTrackerConfigData::CornerDetector::maxNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, maxNumFeatures)) .def_readwrite("enableSobel", &FeatureTrackerConfigData::CornerDetector::enableSobel, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSobel)) @@ -1154,6 +1154,8 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ // FeatureTrackerConfig (after ConfigData) featureTrackerConfig .def(py::init<>()) + .def(py::init>()) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index 0c86cd6c8..baa8fbda5 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -1032,6 +1032,7 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ .def_readonly("passthroughInputImage", &FeatureTracker::passthroughInputImage, DOC(dai, node, FeatureTracker, passthroughInputImage)) .def_readonly("initialConfig", &FeatureTracker::initialConfig, DOC(dai, node, FeatureTracker, initialConfig)) .def("setWaitForConfigInput", &FeatureTracker::setWaitForConfigInput, py::arg("wait"), DOC(dai, node, FeatureTracker, setWaitForConfigInput)) + .def("setHardwareResources", &FeatureTracker::setHardwareResources, py::arg("numShaves"), py::arg("numMemorySlices"), DOC(dai, node, FeatureTracker, setHardwareResources)) ; daiNodeModule.attr("FeatureTracker").attr("Properties") = featureTrackerProperties; From 0517a1a2447cb23f0ad72e43c73bf3b233110899 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 26 Jul 2021 14:44:00 +0300 Subject: [PATCH 10/35] Sync python-cpp examples --- depthai-core | 2 +- examples/corner_detector.py | 27 +++++++++++++-------------- examples/feature_tracker.py | 26 ++++++++++++++++++-------- 3 files changed, 32 insertions(+), 23 deletions(-) diff --git a/depthai-core b/depthai-core index 2637a674f..413449ecf 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 2637a674f0d2b2ced640bda1b07c1afc5cd44e43 +Subproject commit 413449ecf2d0c463ec0e58e5f005a8285cca0fba diff --git a/examples/corner_detector.py b/examples/corner_detector.py index 47f01204c..a8ec006bd 100755 --- a/examples/corner_detector.py +++ b/examples/corner_detector.py @@ -32,17 +32,19 @@ 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) -featureTrackerLeft.initialConfig.setMotionEstimator(False) xinTrackedFeaturesConfig.out.link(featureTrackerLeft.inputConfig) monoRight.out.link(featureTrackerRight.inputImage) featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) -featureTrackerRight.initialConfig.setMotionEstimator(False) xinTrackedFeaturesConfig.out.link(featureTrackerRight.inputConfig) featureTrackerConfig = featureTrackerRight.initialConfig.get() @@ -60,12 +62,14 @@ inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig") - leftWindowName = "left" rightWindowName = "right" - pointColor = (0, 0, 255) - circleRadius = 2 + def drawFeatures(frame, features): + pointColor = (0, 0, 255) + circleRadius = 2 + for feature in features: + cv2.circle(frame, (int(feature.position.x), int(feature.position.y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) while True: inPassthroughFrameLeft = passthroughImageLeftQueue.get() @@ -77,12 +81,10 @@ rightFrame = cv2.cvtColor(passthroughFrameRight, cv2.COLOR_GRAY2BGR) trackedFeaturesLeft = outputFeaturesLeftQueue.get().trackedFeatures - for feature in trackedFeaturesLeft: - cv2.circle(leftFrame, (int(feature.position.x), int(feature.position.y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + drawFeatures(leftFrame, trackedFeaturesLeft) trackedFeaturesRight = outputFeaturesRightQueue.get().trackedFeatures - for feature in trackedFeaturesRight: - cv2.circle(rightFrame, (int(feature.position.x), int(feature.position.y)), circleRadius, pointColor, -1, cv2.LINE_AA, 0) + drawFeatures(rightFrame, trackedFeaturesRight) # Show the frame cv2.imshow(leftWindowName, leftFrame) @@ -94,14 +96,11 @@ elif key == ord('s'): if featureTrackerConfig.cornerDetector.algorithmType == dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS: featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.SHI_THOMASI - print("Switchig to Shi-Thomasi") + print("Switching to Shi-Thomasi") else: featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS - print("Switchig to Harris") + print("Switching to Harris") cfg = dai.FeatureTrackerConfig() cfg.set(featureTrackerConfig) inputFeatureTrackerConfigQueue.send(cfg) - - - pass \ No newline at end of file diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index 60d1d8b9b..8a585b167 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -6,17 +6,18 @@ class FeatureTrackerDrawer: - trackedIDs = None - trackedFeaturesPath = None - lineColor = (200, 0, 200) pointColor = (0, 0, 255) circleRadius = 2 maxTrackedFeaturesPathLength = 30 + # for how many frames the feature is tracked trackedFeaturesPathLength = 10 + trackedIDs = None + trackedFeaturesPath = None + def onTrackBar(self, val): - self.trackedFeaturesPathLength = val + FeatureTrackerDrawer.trackedFeaturesPathLength = val pass def trackFeaturePath(self, features): @@ -32,7 +33,7 @@ def trackFeaturePath(self, features): path = self.trackedFeaturesPath[currentID] path.append(currentFeature.position) - while(len(path) > max(1, self.trackedFeaturesPathLength)): + while(len(path) > max(1, FeatureTrackerDrawer.trackedFeaturesPathLength)): path.popleft() self.trackedFeaturesPath[currentID] = path @@ -49,11 +50,11 @@ def trackFeaturePath(self, features): def drawFeatures(self, img): - # For every feature, + cv2.setTrackbarPos(self.trackbarName, self.windowName, FeatureTrackerDrawer.trackedFeaturesPathLength) + for featurePath in self.trackedFeaturesPath.values(): path = featurePath - # Draw the feature movement path. for j in range(len(path) - 1): src = (int(path[j].x), int(path[j].y)) dst = (int(path[j + 1].x), int(path[j + 1].y)) @@ -62,8 +63,10 @@ def drawFeatures(self, img): cv2.circle(img, (int(path[j].x), int(path[j].y)), self.circleRadius, self.pointColor, -1, cv2.LINE_AA, 0) def __init__(self, trackbarName, windowName): + self.trackbarName = trackbarName + self.windowName = windowName cv2.namedWindow(windowName) - cv2.createTrackbar(trackbarName, windowName, self.trackedFeaturesPathLength, self.maxTrackedFeaturesPathLength, self.onTrackBar) + cv2.createTrackbar(trackbarName, windowName, FeatureTrackerDrawer.trackedFeaturesPathLength, FeatureTrackerDrawer.maxTrackedFeaturesPathLength, self.onTrackBar) self.trackedIDs = set() self.trackedFeaturesPath = dict() @@ -102,6 +105,13 @@ def __init__(self, trackbarName, windowName): featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) +# By default the least mount of resources are allocated +# increasing it improves performance +numShaves = 2 +numMemorySlices = 2 +featureTrackerLeft.setHardwareResources(numShaves, numMemorySlices) +featureTrackerRight.setHardwareResources(numShaves, numMemorySlices) + # Connect to device and start pipeline with dai.Device(pipeline) as device: From f323fb53a773d99368d4366a3cb487e837f530a9 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 27 Jul 2021 16:53:32 +0300 Subject: [PATCH 11/35] Rename FeatureTrackerData to TrackedFeatures --- depthai-core | 2 +- src/DatatypeBindings.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/depthai-core b/depthai-core index 413449ecf..44fbe5262 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 413449ecf2d0c463ec0e58e5f005a8285cca0fba +Subproject commit 44fbe5262d27d97c26f2c4f37dda7aa433eaa610 diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 72b81eaa5..43a0a9be0 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -20,7 +20,7 @@ #include "depthai/pipeline/datatype/IMUData.hpp" #include "depthai/pipeline/datatype/StereoDepthConfig.hpp" #include "depthai/pipeline/datatype/EdgeDetectorConfig.hpp" -#include "depthai/pipeline/datatype/FeatureTrackerData.hpp" +#include "depthai/pipeline/datatype/TrackedFeatures.hpp" #include "depthai/pipeline/datatype/FeatureTrackerConfig.hpp" // depthai-shared @@ -1145,10 +1145,10 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ ; - // Bind FeatureTrackerData - py::class_>(m, "FeatureTrackerData", DOC(dai, FeatureTrackerData)) + // Bind TrackedFeatures + py::class_>(m, "TrackedFeatures", DOC(dai, TrackedFeatures)) .def(py::init<>()) - .def_property("trackedFeatures", [](FeatureTrackerData& feat) { return &feat.trackedFeatures; }, [](FeatureTrackerData& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, FeatureTrackerData, trackedFeatures)) + .def_property("trackedFeatures", [](TrackedFeatures& feat) { return &feat.trackedFeatures; }, [](TrackedFeatures& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, TrackedFeatures, trackedFeatures)) ; // FeatureTrackerConfig (after ConfigData) From 37c1ce8955fc763231b0c70cd241a1170867351a Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 27 Jul 2021 17:42:44 +0300 Subject: [PATCH 12/35] Update core --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 44fbe5262..6ee96e1c0 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 44fbe5262d27d97c26f2c4f37dda7aa433eaa610 +Subproject commit 6ee96e1c0e7c11e9d84015d601927fa4dea8ff80 From 97ddf28e500b373d6134c7e2bab40feb4c655088 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Thu, 29 Jul 2021 16:04:34 +0300 Subject: [PATCH 13/35] Add support for hardware accelerated motion estimation --- depthai-core | 2 +- examples/feature_tracker.py | 22 +++++++++++++++++++++- src/DatatypeBindings.cpp | 2 ++ 3 files changed, 24 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index 6ee96e1c0..7250d5ea1 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 6ee96e1c0e7c11e9d84015d601927fa4dea8ff80 +Subproject commit 7250d5ea1a799ddff33a05fe48fef672af330e62 diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index 8a585b167..eb7032390 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -84,11 +84,13 @@ def __init__(self, trackbarName, windowName): xoutTrackedFeaturesLeft = pipeline.createXLinkOut() xoutPassthroughFrameRight = pipeline.createXLinkOut() xoutTrackedFeaturesRight = pipeline.createXLinkOut() +xinTrackedFeaturesConfig = pipeline.createXLinkIn() xoutPassthroughFrameLeft.setStreamName("passthroughFrameLeft") xoutTrackedFeaturesLeft.setStreamName("trackedFeaturesLeft") xoutPassthroughFrameRight.setStreamName("passthroughFrameRight") xoutTrackedFeaturesRight.setStreamName("trackedFeaturesRight") +xinTrackedFeaturesConfig.setStreamName("trackedFeaturesConfig") # Properties monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) @@ -100,10 +102,12 @@ def __init__(self, trackbarName, windowName): 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 @@ -112,6 +116,9 @@ def __init__(self, trackbarName, windowName): featureTrackerLeft.setHardwareResources(numShaves, numMemorySlices) featureTrackerRight.setHardwareResources(numShaves, numMemorySlices) +featureTrackerConfig = featureTrackerRight.initialConfig.get() +print("Press 's' to switch between Lucas-Kanade optical flow and hardware accelerated motion estimation!") + # Connect to device and start pipeline with dai.Device(pipeline) as device: @@ -121,6 +128,8 @@ def __init__(self, trackbarName, windowName): passthroughImageRightQueue = device.getOutputQueue("passthroughFrameRight", 8, False) outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, False) + inputFeatureTrackerConfigQueue = device.getInputQueue("trackedFeaturesConfig") + leftWindowName = "left" leftFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", leftWindowName) @@ -150,4 +159,15 @@ def __init__(self, trackbarName, windowName): key = cv2.waitKey(1) if key == ord('q'): - break \ No newline at end of file + break + elif key == ord('s'): + if featureTrackerConfig.motionEstimator.algorithmType == dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.LUCAS_KANADE_OPTICAL_FLOW: + featureTrackerConfig.motionEstimator.algorithmType = dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.HW_MOTION_ESTIMATION + print("Switching to hardware accelerated motion estimation") + else: + featureTrackerConfig.motionEstimator.algorithmType = dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.LUCAS_KANADE_OPTICAL_FLOW + print("Switching to Lucas-Kanade optical flow") + + cfg = dai.FeatureTrackerConfig() + cfg.set(featureTrackerConfig) + inputFeatureTrackerConfigQueue.send(cfg) diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 43a0a9be0..6eed56a67 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -1118,6 +1118,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ motionEstimatorType .value("LUCAS_KANADE_OPTICAL_FLOW", FeatureTrackerConfigData::MotionEstimator::AlgorithmType::LUCAS_KANADE_OPTICAL_FLOW) + .value("HW_MOTION_ESTIMATION", FeatureTrackerConfigData::MotionEstimator::AlgorithmType::HW_MOTION_ESTIMATION) ; motionEstimatorOpticalFlow @@ -1161,6 +1162,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) .def("setOpticalFlow", &FeatureTrackerConfig::setOpticalFlow, py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) + .def("setHwMotionEstimation", &FeatureTrackerConfig::setHwMotionEstimation, DOC(dai, FeatureTrackerConfig, setHwMotionEstimation)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) .def("setTargetNumFeatures", &FeatureTrackerConfig::setTargetNumFeatures, py::arg("targetNumFeatures"), DOC(dai, FeatureTrackerConfig, setTargetNumFeatures)) From e04d9e7aae08b54de1c65e64a126bf3fcb504a45 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 30 Jul 2021 01:12:49 +0300 Subject: [PATCH 14/35] Rename feature tracker config fields --- depthai-core | 2 +- examples/corner_detector.py | 6 +++--- examples/feature_tracker.py | 6 +++--- src/DatatypeBindings.cpp | 24 ++++++++++++------------ 4 files changed, 19 insertions(+), 19 deletions(-) diff --git a/depthai-core b/depthai-core index 7250d5ea1..e197a862e 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 7250d5ea1a799ddff33a05fe48fef672af330e62 +Subproject commit e197a862ebbbc852a293452df142e94029d37f74 diff --git a/examples/corner_detector.py b/examples/corner_detector.py index a8ec006bd..9c90514a7 100755 --- a/examples/corner_detector.py +++ b/examples/corner_detector.py @@ -94,11 +94,11 @@ def drawFeatures(frame, features): if key == ord('q'): break elif key == ord('s'): - if featureTrackerConfig.cornerDetector.algorithmType == dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS: - featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.SHI_THOMASI + if featureTrackerConfig.cornerDetector.type == dai.FeatureTrackerConfigData.CornerDetector.Type.HARRIS: + featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfigData.CornerDetector.Type.SHI_THOMASI print("Switching to Shi-Thomasi") else: - featureTrackerConfig.cornerDetector.algorithmType = dai.FeatureTrackerConfigData.CornerDetector.AlgorithmType.HARRIS + featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfigData.CornerDetector.Type.HARRIS print("Switching to Harris") cfg = dai.FeatureTrackerConfig() diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index eb7032390..a5911aa23 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -161,11 +161,11 @@ def __init__(self, trackbarName, windowName): if key == ord('q'): break elif key == ord('s'): - if featureTrackerConfig.motionEstimator.algorithmType == dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.LUCAS_KANADE_OPTICAL_FLOW: - featureTrackerConfig.motionEstimator.algorithmType = dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.HW_MOTION_ESTIMATION + if featureTrackerConfig.motionEstimator.type == dai.FeatureTrackerConfigData.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW: + featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfigData.MotionEstimator.Type.HW_MOTION_ESTIMATION print("Switching to hardware accelerated motion estimation") else: - featureTrackerConfig.motionEstimator.algorithmType = dai.FeatureTrackerConfigData.MotionEstimator.AlgorithmType.LUCAS_KANADE_OPTICAL_FLOW + featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfigData.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW print("Switching to Lucas-Kanade optical flow") cfg = dai.FeatureTrackerConfig() diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 6eed56a67..2c771740f 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -116,10 +116,10 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ py::class_> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); py::class_ featureTrackerConfigData(m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)); py::class_ cornerDetector(featureTrackerConfigData, "CornerDetector", DOC(dai, FeatureTrackerConfigData, CornerDetector)); - py::enum_ cornerDetectorType(cornerDetector, "AlgorithmType", DOC(dai, FeatureTrackerConfigData, CornerDetector, AlgorithmType)); + py::enum_ cornerDetectorType(cornerDetector, "Type", DOC(dai, FeatureTrackerConfigData, CornerDetector, Type)); py::class_ cornerDetectorThresholds(cornerDetector, "Thresholds", DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds)); py::class_ motionEstimator(featureTrackerConfigData, "MotionEstimator", DOC(dai, FeatureTrackerConfigData, MotionEstimator)); - py::enum_ motionEstimatorType(motionEstimator, "AlgorithmType", DOC(dai, FeatureTrackerConfigData, MotionEstimator, AlgorithmType)); + py::enum_ motionEstimatorType(motionEstimator, "Type", DOC(dai, FeatureTrackerConfigData, MotionEstimator, Type)); py::class_ motionEstimatorOpticalFlow(motionEstimator, "OpticalFlow", DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow)); py::class_ featureMaintainer(featureTrackerConfigData, "FeatureMaintainer", DOC(dai, FeatureTrackerConfigData, FeatureMaintainer)); @@ -1092,8 +1092,8 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ ; cornerDetectorType - .value("HARRIS", FeatureTrackerConfigData::CornerDetector::AlgorithmType::HARRIS) - .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::AlgorithmType::SHI_THOMASI) + .value("HARRIS", FeatureTrackerConfigData::CornerDetector::Type::HARRIS) + .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::Type::SHI_THOMASI) ; cornerDetectorThresholds @@ -1107,18 +1107,18 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ cornerDetector .def(py::init<>()) - .def_readwrite("algorithmType", &FeatureTrackerConfigData::CornerDetector::algorithmType, DOC(dai, FeatureTrackerConfigData, CornerDetector, algorithmType)) + .def_readwrite("type", &FeatureTrackerConfigData::CornerDetector::type, DOC(dai, FeatureTrackerConfigData, CornerDetector, type)) .def_readwrite("cellGridDimension", &FeatureTrackerConfigData::CornerDetector::cellGridDimension, DOC(dai, FeatureTrackerConfigData, CornerDetector, cellGridDimension)) - .def_readwrite("targetNumFeatures", &FeatureTrackerConfigData::CornerDetector::targetNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, targetNumFeatures)) - .def_readwrite("maxNumFeatures", &FeatureTrackerConfigData::CornerDetector::maxNumFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, maxNumFeatures)) + .def_readwrite("numTargetFeatures", &FeatureTrackerConfigData::CornerDetector::numTargetFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, numTargetFeatures)) + .def_readwrite("numMaxFeatures", &FeatureTrackerConfigData::CornerDetector::numMaxFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, numMaxFeatures)) .def_readwrite("enableSobel", &FeatureTrackerConfigData::CornerDetector::enableSobel, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSobel)) .def_readwrite("enableSorting", &FeatureTrackerConfigData::CornerDetector::enableSorting, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSorting)) .def_readwrite("thresholds", &FeatureTrackerConfigData::CornerDetector::thresholds, DOC(dai, FeatureTrackerConfigData, CornerDetector, thresholds)) ; motionEstimatorType - .value("LUCAS_KANADE_OPTICAL_FLOW", FeatureTrackerConfigData::MotionEstimator::AlgorithmType::LUCAS_KANADE_OPTICAL_FLOW) - .value("HW_MOTION_ESTIMATION", FeatureTrackerConfigData::MotionEstimator::AlgorithmType::HW_MOTION_ESTIMATION) + .value("LUCAS_KANADE_OPTICAL_FLOW", FeatureTrackerConfigData::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) + .value("HW_MOTION_ESTIMATION", FeatureTrackerConfigData::MotionEstimator::Type::HW_MOTION_ESTIMATION) ; motionEstimatorOpticalFlow @@ -1133,7 +1133,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ motionEstimator .def(py::init<>()) .def_readwrite("enable", &FeatureTrackerConfigData::MotionEstimator::enable, DOC(dai, FeatureTrackerConfigData, MotionEstimator, enable)) - .def_readwrite("algorithmType", &FeatureTrackerConfigData::MotionEstimator::algorithmType, DOC(dai, FeatureTrackerConfigData, MotionEstimator, algorithmType)) + .def_readwrite("type", &FeatureTrackerConfigData::MotionEstimator::type, DOC(dai, FeatureTrackerConfigData, MotionEstimator, type)) .def_readwrite("opticalFlow", &FeatureTrackerConfigData::MotionEstimator::opticalFlow, DOC(dai, FeatureTrackerConfigData, MotionEstimator, opticalFlow)) ; @@ -1157,7 +1157,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def(py::init<>()) .def(py::init>()) - .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) @@ -1165,7 +1165,7 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def("setHwMotionEstimation", &FeatureTrackerConfig::setHwMotionEstimation, DOC(dai, FeatureTrackerConfig, setHwMotionEstimation)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) - .def("setTargetNumFeatures", &FeatureTrackerConfig::setTargetNumFeatures, py::arg("targetNumFeatures"), DOC(dai, FeatureTrackerConfig, setTargetNumFeatures)) + .def("setNumTargetFeatures", &FeatureTrackerConfig::setNumTargetFeatures, py::arg("numTargetFeatures"), DOC(dai, FeatureTrackerConfig, setNumTargetFeatures)) .def("set", &FeatureTrackerConfig::set, py::arg("config"), DOC(dai, FeatureTrackerConfig, set)) .def("get", &FeatureTrackerConfig::get, DOC(dai, FeatureTrackerConfig, get)) From 6ceb90605177492d1b85f37ff703e26f14c949f5 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 30 Jul 2021 03:00:04 +0300 Subject: [PATCH 15/35] Refactor FeatureTrackerConfig --- depthai-core | 2 +- examples/corner_detector.py | 6 +-- examples/feature_tracker.py | 6 +-- src/DatatypeBindings.cpp | 97 ++++++++++++++++++------------------- 4 files changed, 55 insertions(+), 56 deletions(-) diff --git a/depthai-core b/depthai-core index e197a862e..fba431c95 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit e197a862ebbbc852a293452df142e94029d37f74 +Subproject commit fba431c957e5133c59ea5b8d3fea762a27844749 diff --git a/examples/corner_detector.py b/examples/corner_detector.py index 9c90514a7..53967b9f2 100755 --- a/examples/corner_detector.py +++ b/examples/corner_detector.py @@ -94,11 +94,11 @@ def drawFeatures(frame, features): if key == ord('q'): break elif key == ord('s'): - if featureTrackerConfig.cornerDetector.type == dai.FeatureTrackerConfigData.CornerDetector.Type.HARRIS: - featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfigData.CornerDetector.Type.SHI_THOMASI + if featureTrackerConfig.cornerDetector.type == dai.FeatureTrackerConfig.CornerDetector.Type.HARRIS: + featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfig.CornerDetector.Type.SHI_THOMASI print("Switching to Shi-Thomasi") else: - featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfigData.CornerDetector.Type.HARRIS + featureTrackerConfig.cornerDetector.type = dai.FeatureTrackerConfig.CornerDetector.Type.HARRIS print("Switching to Harris") cfg = dai.FeatureTrackerConfig() diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index a5911aa23..3dce3c615 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -161,11 +161,11 @@ def __init__(self, trackbarName, windowName): if key == ord('q'): break elif key == ord('s'): - if featureTrackerConfig.motionEstimator.type == dai.FeatureTrackerConfigData.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW: - featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfigData.MotionEstimator.Type.HW_MOTION_ESTIMATION + if featureTrackerConfig.motionEstimator.type == dai.FeatureTrackerConfig.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW: + featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfig.MotionEstimator.Type.HW_MOTION_ESTIMATION print("Switching to hardware accelerated motion estimation") else: - featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfigData.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW + featureTrackerConfig.motionEstimator.type = dai.FeatureTrackerConfig.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW print("Switching to Lucas-Kanade optical flow") cfg = dai.FeatureTrackerConfig() diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 2c771740f..3558a42b1 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -114,15 +114,14 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ py::class_> rawTrackedFeatures(m, "RawTrackedFeatures", DOC(dai, RawTrackedFeatures)); py::class_ trackedFeature(m, "TrackedFeature", DOC(dai, TrackedFeature)); py::class_> rawFeatureTrackerConfig(m, "RawFeatureTrackerConfig", DOC(dai, RawFeatureTrackerConfig)); - py::class_ featureTrackerConfigData(m, "FeatureTrackerConfigData", DOC(dai, FeatureTrackerConfigData)); - py::class_ cornerDetector(featureTrackerConfigData, "CornerDetector", DOC(dai, FeatureTrackerConfigData, CornerDetector)); - py::enum_ cornerDetectorType(cornerDetector, "Type", DOC(dai, FeatureTrackerConfigData, CornerDetector, Type)); - py::class_ cornerDetectorThresholds(cornerDetector, "Thresholds", DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds)); - py::class_ motionEstimator(featureTrackerConfigData, "MotionEstimator", DOC(dai, FeatureTrackerConfigData, MotionEstimator)); - py::enum_ motionEstimatorType(motionEstimator, "Type", DOC(dai, FeatureTrackerConfigData, MotionEstimator, Type)); - py::class_ motionEstimatorOpticalFlow(motionEstimator, "OpticalFlow", DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow)); - - py::class_ featureMaintainer(featureTrackerConfigData, "FeatureMaintainer", DOC(dai, FeatureTrackerConfigData, FeatureMaintainer)); + py::class_ cornerDetector(rawFeatureTrackerConfig, "CornerDetector", DOC(dai, RawFeatureTrackerConfig, CornerDetector)); + py::enum_ cornerDetectorType(cornerDetector, "Type", DOC(dai, RawFeatureTrackerConfig, CornerDetector, Type)); + py::class_ cornerDetectorThresholds(cornerDetector, "Thresholds", DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds)); + py::class_ motionEstimator(rawFeatureTrackerConfig, "MotionEstimator", DOC(dai, RawFeatureTrackerConfig, MotionEstimator)); + py::enum_ motionEstimatorType(motionEstimator, "Type", DOC(dai, RawFeatureTrackerConfig, MotionEstimator, Type)); + py::class_ motionEstimatorOpticalFlow(motionEstimator, "OpticalFlow", DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow)); + + py::class_ featureMaintainer(rawFeatureTrackerConfig, "FeatureMaintainer", DOC(dai, RawFeatureTrackerConfig, FeatureMaintainer)); py::class_> featureTrackerConfig(m, "FeatureTrackerConfig", DOC(dai, FeatureTrackerConfig)); @@ -1079,70 +1078,66 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ ; - rawFeatureTrackerConfig - .def(py::init<>()) - .def_readwrite("config", &RawFeatureTrackerConfig::config) - ; - featureTrackerConfigData + rawFeatureTrackerConfig .def(py::init<>()) - .def_readwrite("cornerDetector", &FeatureTrackerConfigData::cornerDetector, DOC(dai, FeatureTrackerConfigData, cornerDetector)) - .def_readwrite("motionEstimator", &FeatureTrackerConfigData::motionEstimator, DOC(dai, FeatureTrackerConfigData, motionEstimator)) - .def_readwrite("featureMaintainer", &FeatureTrackerConfigData::featureMaintainer, DOC(dai, FeatureTrackerConfigData, featureMaintainer)) + .def_readwrite("cornerDetector", &RawFeatureTrackerConfig::cornerDetector, DOC(dai, RawFeatureTrackerConfig, cornerDetector)) + .def_readwrite("motionEstimator", &RawFeatureTrackerConfig::motionEstimator, DOC(dai, RawFeatureTrackerConfig, motionEstimator)) + .def_readwrite("featureMaintainer", &RawFeatureTrackerConfig::featureMaintainer, DOC(dai, RawFeatureTrackerConfig, featureMaintainer)) ; cornerDetectorType - .value("HARRIS", FeatureTrackerConfigData::CornerDetector::Type::HARRIS) - .value("SHI_THOMASI", FeatureTrackerConfigData::CornerDetector::Type::SHI_THOMASI) + .value("HARRIS", RawFeatureTrackerConfig::CornerDetector::Type::HARRIS) + .value("SHI_THOMASI", RawFeatureTrackerConfig::CornerDetector::Type::SHI_THOMASI) ; cornerDetectorThresholds .def(py::init<>()) - .def_readwrite("initialValue", &FeatureTrackerConfigData::CornerDetector::Thresholds::initialValue, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, initialValue)) - .def_readwrite("min", &FeatureTrackerConfigData::CornerDetector::Thresholds::min, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, min)) - .def_readwrite("max", &FeatureTrackerConfigData::CornerDetector::Thresholds::max, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, max)) - .def_readwrite("decreaseFactor", &FeatureTrackerConfigData::CornerDetector::Thresholds::decreaseFactor, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, decreaseFactor)) - .def_readwrite("increaseFactor", &FeatureTrackerConfigData::CornerDetector::Thresholds::increaseFactor, DOC(dai, FeatureTrackerConfigData, CornerDetector, Thresholds, increaseFactor)) + .def_readwrite("initialValue", &RawFeatureTrackerConfig::CornerDetector::Thresholds::initialValue, DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds, initialValue)) + .def_readwrite("min", &RawFeatureTrackerConfig::CornerDetector::Thresholds::min, DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds, min)) + .def_readwrite("max", &RawFeatureTrackerConfig::CornerDetector::Thresholds::max, DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds, max)) + .def_readwrite("decreaseFactor", &RawFeatureTrackerConfig::CornerDetector::Thresholds::decreaseFactor, DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds, decreaseFactor)) + .def_readwrite("increaseFactor", &RawFeatureTrackerConfig::CornerDetector::Thresholds::increaseFactor, DOC(dai, RawFeatureTrackerConfig, CornerDetector, Thresholds, increaseFactor)) ; cornerDetector .def(py::init<>()) - .def_readwrite("type", &FeatureTrackerConfigData::CornerDetector::type, DOC(dai, FeatureTrackerConfigData, CornerDetector, type)) - .def_readwrite("cellGridDimension", &FeatureTrackerConfigData::CornerDetector::cellGridDimension, DOC(dai, FeatureTrackerConfigData, CornerDetector, cellGridDimension)) - .def_readwrite("numTargetFeatures", &FeatureTrackerConfigData::CornerDetector::numTargetFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, numTargetFeatures)) - .def_readwrite("numMaxFeatures", &FeatureTrackerConfigData::CornerDetector::numMaxFeatures, DOC(dai, FeatureTrackerConfigData, CornerDetector, numMaxFeatures)) - .def_readwrite("enableSobel", &FeatureTrackerConfigData::CornerDetector::enableSobel, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSobel)) - .def_readwrite("enableSorting", &FeatureTrackerConfigData::CornerDetector::enableSorting, DOC(dai, FeatureTrackerConfigData, CornerDetector, enableSorting)) - .def_readwrite("thresholds", &FeatureTrackerConfigData::CornerDetector::thresholds, DOC(dai, FeatureTrackerConfigData, CornerDetector, thresholds)) + .def_readwrite("type", &RawFeatureTrackerConfig::CornerDetector::type, DOC(dai, RawFeatureTrackerConfig, CornerDetector, type)) + .def_readwrite("cellGridDimension", &RawFeatureTrackerConfig::CornerDetector::cellGridDimension, DOC(dai, RawFeatureTrackerConfig, CornerDetector, cellGridDimension)) + .def_readwrite("numTargetFeatures", &RawFeatureTrackerConfig::CornerDetector::numTargetFeatures, DOC(dai, RawFeatureTrackerConfig, CornerDetector, numTargetFeatures)) + .def_readwrite("numMaxFeatures", &RawFeatureTrackerConfig::CornerDetector::numMaxFeatures, DOC(dai, RawFeatureTrackerConfig, CornerDetector, numMaxFeatures)) + .def_readwrite("enableSobel", &RawFeatureTrackerConfig::CornerDetector::enableSobel, DOC(dai, RawFeatureTrackerConfig, CornerDetector, enableSobel)) + .def_readwrite("enableSorting", &RawFeatureTrackerConfig::CornerDetector::enableSorting, DOC(dai, RawFeatureTrackerConfig, CornerDetector, enableSorting)) + .def_readwrite("thresholds", &RawFeatureTrackerConfig::CornerDetector::thresholds, DOC(dai, RawFeatureTrackerConfig, CornerDetector, thresholds)) ; motionEstimatorType - .value("LUCAS_KANADE_OPTICAL_FLOW", FeatureTrackerConfigData::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) - .value("HW_MOTION_ESTIMATION", FeatureTrackerConfigData::MotionEstimator::Type::HW_MOTION_ESTIMATION) + .value("LUCAS_KANADE_OPTICAL_FLOW", RawFeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) + .value("HW_MOTION_ESTIMATION", RawFeatureTrackerConfig::MotionEstimator::Type::HW_MOTION_ESTIMATION) ; motionEstimatorOpticalFlow .def(py::init<>()) - .def_readwrite("pyramidLevels", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::pyramidLevels, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, pyramidLevels)) - .def_readwrite("searchWindowWidth", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::searchWindowWidth, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, searchWindowWidth)) - .def_readwrite("searchWindowHeight", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::searchWindowHeight, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, searchWindowHeight)) - .def_readwrite("epsilon", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::epsilon, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, epsilon)) - .def_readwrite("maxIterations", &FeatureTrackerConfigData::MotionEstimator::OpticalFlow::maxIterations, DOC(dai, FeatureTrackerConfigData, MotionEstimator, OpticalFlow, maxIterations)) + .def_readwrite("pyramidLevels", &RawFeatureTrackerConfig::MotionEstimator::OpticalFlow::pyramidLevels, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow, pyramidLevels)) + .def_readwrite("searchWindowWidth", &RawFeatureTrackerConfig::MotionEstimator::OpticalFlow::searchWindowWidth, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow, searchWindowWidth)) + .def_readwrite("searchWindowHeight", &RawFeatureTrackerConfig::MotionEstimator::OpticalFlow::searchWindowHeight, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow, searchWindowHeight)) + .def_readwrite("epsilon", &RawFeatureTrackerConfig::MotionEstimator::OpticalFlow::epsilon, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow, epsilon)) + .def_readwrite("maxIterations", &RawFeatureTrackerConfig::MotionEstimator::OpticalFlow::maxIterations, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, OpticalFlow, maxIterations)) ; motionEstimator .def(py::init<>()) - .def_readwrite("enable", &FeatureTrackerConfigData::MotionEstimator::enable, DOC(dai, FeatureTrackerConfigData, MotionEstimator, enable)) - .def_readwrite("type", &FeatureTrackerConfigData::MotionEstimator::type, DOC(dai, FeatureTrackerConfigData, MotionEstimator, type)) - .def_readwrite("opticalFlow", &FeatureTrackerConfigData::MotionEstimator::opticalFlow, DOC(dai, FeatureTrackerConfigData, MotionEstimator, opticalFlow)) + .def_readwrite("enable", &RawFeatureTrackerConfig::MotionEstimator::enable, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, enable)) + .def_readwrite("type", &RawFeatureTrackerConfig::MotionEstimator::type, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, type)) + .def_readwrite("opticalFlow", &RawFeatureTrackerConfig::MotionEstimator::opticalFlow, DOC(dai, RawFeatureTrackerConfig, MotionEstimator, opticalFlow)) ; featureMaintainer .def(py::init<>()) - .def_readwrite("enable", &FeatureTrackerConfigData::FeatureMaintainer::enable, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, enable)) - .def_readwrite("minimumDistanceBetweenFeatures", &FeatureTrackerConfigData::FeatureMaintainer::minimumDistanceBetweenFeatures, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, minimumDistanceBetweenFeatures)) - .def_readwrite("lostFeatureErrorThreshold", &FeatureTrackerConfigData::FeatureMaintainer::lostFeatureErrorThreshold, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, lostFeatureErrorThreshold)) - .def_readwrite("trackedFeatureThreshold", &FeatureTrackerConfigData::FeatureMaintainer::trackedFeatureThreshold, DOC(dai, FeatureTrackerConfigData, FeatureMaintainer, trackedFeatureThreshold)) + .def_readwrite("enable", &RawFeatureTrackerConfig::FeatureMaintainer::enable, DOC(dai, RawFeatureTrackerConfig, FeatureMaintainer, enable)) + .def_readwrite("minimumDistanceBetweenFeatures", &RawFeatureTrackerConfig::FeatureMaintainer::minimumDistanceBetweenFeatures, DOC(dai, RawFeatureTrackerConfig, FeatureMaintainer, minimumDistanceBetweenFeatures)) + .def_readwrite("lostFeatureErrorThreshold", &RawFeatureTrackerConfig::FeatureMaintainer::lostFeatureErrorThreshold, DOC(dai, RawFeatureTrackerConfig, FeatureMaintainer, lostFeatureErrorThreshold)) + .def_readwrite("trackedFeatureThreshold", &RawFeatureTrackerConfig::FeatureMaintainer::trackedFeatureThreshold, DOC(dai, RawFeatureTrackerConfig, FeatureMaintainer, trackedFeatureThreshold)) ; @@ -1157,18 +1152,22 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def(py::init<>()) .def(py::init>()) - .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) - .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) - .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) + .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) .def("setOpticalFlow", &FeatureTrackerConfig::setOpticalFlow, py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) .def("setHwMotionEstimation", &FeatureTrackerConfig::setHwMotionEstimation, DOC(dai, FeatureTrackerConfig, setHwMotionEstimation)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) - .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) + .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) .def("setNumTargetFeatures", &FeatureTrackerConfig::setNumTargetFeatures, py::arg("numTargetFeatures"), DOC(dai, FeatureTrackerConfig, setNumTargetFeatures)) .def("set", &FeatureTrackerConfig::set, py::arg("config"), DOC(dai, FeatureTrackerConfig, set)) .def("get", &FeatureTrackerConfig::get, DOC(dai, FeatureTrackerConfig, get)) ; + // add aliases + m.attr("FeatureTrackerConfig").attr("CornerDetector") = m.attr("RawFeatureTrackerConfig").attr("CornerDetector"); + m.attr("FeatureTrackerConfig").attr("MotionEstimator") = m.attr("RawFeatureTrackerConfig").attr("MotionEstimator"); + } From b6f93d834c757a4f901da665f459608f21cf4549 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sat, 31 Jul 2021 19:23:47 +0300 Subject: [PATCH 16/35] Update core --- depthai-core | 2 +- src/DatatypeBindings.cpp | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 48c148f48..58f023e66 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 48c148f4887399844862a9c6a8589beb7bbef9ba +Subproject commit 58f023e66157ddc7e1768ac130e9c91cb0a95b68 diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 3558a42b1..37bacb716 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -1169,5 +1169,6 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ // add aliases m.attr("FeatureTrackerConfig").attr("CornerDetector") = m.attr("RawFeatureTrackerConfig").attr("CornerDetector"); m.attr("FeatureTrackerConfig").attr("MotionEstimator") = m.attr("RawFeatureTrackerConfig").attr("MotionEstimator"); + m.attr("FeatureTrackerConfig").attr("FeatureMaintainer") = m.attr("RawFeatureTrackerConfig").attr("FeatureMaintainer"); } From 209927a47657329fea24522a81274d495e0dad08 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 2 Aug 2021 12:33:55 +0300 Subject: [PATCH 17/35] Update bindings --- depthai-core | 2 +- src/DatatypeBindings.cpp | 11 ++++++----- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/depthai-core b/depthai-core index 58f023e66..0afa0d5eb 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 58f023e66157ddc7e1768ac130e9c91cb0a95b68 +Subproject commit 0afa0d5eb898f2a1f9eb32fcdfa4a11f101ae70f diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 37bacb716..12c82c307 100644 --- a/src/DatatypeBindings.cpp +++ b/src/DatatypeBindings.cpp @@ -1152,14 +1152,15 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def(py::init<>()) .def(py::init>()) - .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) - .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("cornerDetector"), DOC(dai, FeatureTrackerConfig, setCornerDetector)) + .def("setCornerDetector", static_cast(&FeatureTrackerConfig::setCornerDetector), py::arg("config"), DOC(dai, FeatureTrackerConfig, setCornerDetector, 2)) .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setMotionEstimator)) - .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) - .def("setOpticalFlow", &FeatureTrackerConfig::setOpticalFlow, py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) + .def("setMotionEstimator", static_cast(&FeatureTrackerConfig::setMotionEstimator), py::arg("config"), DOC(dai, FeatureTrackerConfig, setMotionEstimator, 2)) + .def("setOpticalFlow", static_cast(&FeatureTrackerConfig::setOpticalFlow), DOC(dai, FeatureTrackerConfig, setOpticalFlow)) + .def("setOpticalFlow", static_cast(&FeatureTrackerConfig::setOpticalFlow), py::arg("config"), DOC(dai, FeatureTrackerConfig, setOpticalFlow, 2)) .def("setHwMotionEstimation", &FeatureTrackerConfig::setHwMotionEstimation, DOC(dai, FeatureTrackerConfig, setHwMotionEstimation)) .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("enable"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer)) - .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) + .def("setFeatureMaintainer", static_cast(&FeatureTrackerConfig::setFeatureMaintainer), py::arg("config"), DOC(dai, FeatureTrackerConfig, setFeatureMaintainer, 2)) .def("setNumTargetFeatures", &FeatureTrackerConfig::setNumTargetFeatures, py::arg("numTargetFeatures"), DOC(dai, FeatureTrackerConfig, setNumTargetFeatures)) .def("set", &FeatureTrackerConfig::set, py::arg("config"), DOC(dai, FeatureTrackerConfig, set)) From b0093c7d53d013f3ed9b1a6413f6211d985e8ab9 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 2 Aug 2021 19:41:59 +0300 Subject: [PATCH 18/35] Update core --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 0afa0d5eb..05793690a 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 0afa0d5eb898f2a1f9eb32fcdfa4a11f101ae70f +Subproject commit 05793690acf5686278be30bdf6aa0abd51f4e563 From 8079d78640176d5a14219fa491910fae2b8b26f7 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Tue, 3 Aug 2021 18:37:26 +0200 Subject: [PATCH 19/35] Added python bindings for DeviceBase --- depthai-core | 2 +- src/DeviceBindings.cpp | 195 ++++++++++++++++++++--------------------- 2 files changed, 94 insertions(+), 103 deletions(-) diff --git a/depthai-core b/depthai-core index 7471b2d3e..3036b2bdb 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 7471b2d3e4f11027a5a7b1d40564738d407d7c79 +Subproject commit 3036b2bdb47459c2531c04c1626cc05c5c3c6741 diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 3f242a698..296de4a78 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -12,46 +12,9 @@ // Searches for available devices (as Device constructor) // but pooling, to check for python interrupts, and releases GIL in between -static std::unique_ptr deviceConstructorHelper(const dai::Pipeline& pipeline, const std::string& pathToCmd = "", bool usb2Mode = false){ - auto startTime = std::chrono::steady_clock::now(); - bool found; - dai::DeviceInfo deviceInfo = {}; - do { - { - // releases python GIL - py::gil_scoped_release release; - std::tie(found, deviceInfo) = dai::Device::getFirstAvailableDevice(); - // Check if found - if(found){ - break; - } else { - // block for 100ms - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - } - } - // reacquires python GIL for PyErr_CheckSignals call - // check if interrupt triggered in between - if (PyErr_CheckSignals() != 0) throw py::error_already_set(); - } while(std::chrono::steady_clock::now() - startTime < dai::Device::DEFAULT_SEARCH_TIME); - - // If neither UNBOOTED nor BOOTLOADER were found (after 'DEFAULT_SEARCH_TIME'), try BOOTED - if(!found) std::tie(found, deviceInfo) = dai::XLinkConnection::getFirstDevice(X_LINK_BOOTED); - - // if no devices found, then throw - if(!found) throw std::runtime_error("No available devices"); - // Check if pathToCmd supplied - if(pathToCmd.empty()){ - return std::unique_ptr(new dai::Device(pipeline, deviceInfo, usb2Mode)); - } else { - return std::unique_ptr(new dai::Device(pipeline, deviceInfo, pathToCmd)); - } - return nullptr; -} - -// Searches for available devices (as Device constructor) -// but pooling, to check for python interrupts, and releases GIL in between -static std::unique_ptr deviceConstructorHelper(dai::OpenVINO::Version version, const std::string& pathToCmd = "", bool usb2Mode = false){ +template +static std::unique_ptr deviceConstructorHelper(const ARG1& arg, const std::string& pathToCmd = "", bool usb2Mode = false){ auto startTime = std::chrono::steady_clock::now(); bool found; dai::DeviceInfo deviceInfo = {}; @@ -59,7 +22,7 @@ static std::unique_ptr deviceConstructorHelper(dai::OpenVINO::Versi { // releases python GIL py::gil_scoped_release release; - std::tie(found, deviceInfo) = dai::Device::getFirstAvailableDevice(); + std::tie(found, deviceInfo) = DEVICE::getFirstAvailableDevice(); // Check if found if(found){ break; @@ -71,7 +34,7 @@ static std::unique_ptr deviceConstructorHelper(dai::OpenVINO::Versi // reacquires python GIL for PyErr_CheckSignals call // check if interrupt triggered in between if (PyErr_CheckSignals() != 0) throw py::error_already_set(); - } while(std::chrono::steady_clock::now() - startTime < dai::Device::DEFAULT_SEARCH_TIME); + } while(std::chrono::steady_clock::now() - startTime < DEVICE::DEFAULT_SEARCH_TIME); // If neither UNBOOTED nor BOOTLOADER were found (after 'DEFAULT_SEARCH_TIME'), try BOOTED if(!found) std::tie(found, deviceInfo) = dai::XLinkConnection::getFirstDevice(X_LINK_BOOTED); @@ -81,9 +44,9 @@ static std::unique_ptr deviceConstructorHelper(dai::OpenVINO::Versi // Check if pathToCmd supplied if(pathToCmd.empty()){ - return std::unique_ptr(new dai::Device(version, deviceInfo, usb2Mode)); + return std::make_unique(arg, deviceInfo, usb2Mode); } else { - return std::unique_ptr(new dai::Device(version, deviceInfo, pathToCmd)); + return std::make_unique(arg, deviceInfo, pathToCmd); } return nullptr; } @@ -117,7 +80,8 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; // Type definitions - py::class_ device(m, "Device", DOC(dai, Device)); + py::class_ deviceBase(m, "DeviceBase", DOC(dai, DeviceBase)); + py::class_ device(m, "Device", DOC(dai, Device)); /////////////////////////////////////////////////////////////////////// @@ -135,67 +99,71 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ // Bind Device, using DeviceWrapper to be able to destruct the object by calling close() - device + deviceBase // Python only methods .def("__enter__", [](py::object obj){ return obj; }) - .def("__exit__", [](Device& d, py::object type, py::object value, py::object traceback) { + .def("__exit__", [](DeviceBase& d, py::object type, py::object value, py::object traceback) { py::gil_scoped_release release; d.close(); }) - .def("close", [](Device& d) { py::gil_scoped_release release; d.close(); }, "Closes the connection to device. Better alternative is the usage of context manager: `with depthai.Device(pipeline) as device:`") - .def("isClosed", &Device::isClosed, "Check if the device is still connected`") + .def("close", [](DeviceBase& d) { py::gil_scoped_release release; d.close(); }, "Closes the connection to device. Better alternative is the usage of context manager: `with depthai.Device(pipeline) as device:`") + .def("isClosed", &DeviceBase::isClosed, "Check if the device is still connected`") //dai::Device methods //static - .def_static("getAnyAvailableDevice", [](std::chrono::microseconds us){ return Device::getAnyAvailableDevice(us); }, py::arg("timeout"), DOC(dai, Device, getAnyAvailableDevice)) - .def_static("getAnyAvailableDevice", [](){ return Device::getAnyAvailableDevice(); }, DOC(dai, Device, getAnyAvailableDevice, 2)) - .def_static("getFirstAvailableDevice", &Device::getFirstAvailableDevice, DOC(dai, Device, getFirstAvailableDevice)) - .def_static("getAllAvailableDevices", &Device::getAllAvailableDevices, DOC(dai, Device, getAllAvailableDevices)) - .def_static("getEmbeddedDeviceBinary", &Device::getEmbeddedDeviceBinary, py::arg("usb2Mode"), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Device, getEmbeddedDeviceBinary)) - .def_static("getDeviceByMxId", &Device::getDeviceByMxId, py::arg("mxId"), DOC(dai, Device, getDeviceByMxId)) + .def_static("getAnyAvailableDevice", [](std::chrono::microseconds us){ return Device::getAnyAvailableDevice(us); }, py::arg("timeout"), DOC(dai, DeviceBase, getAnyAvailableDevice)) + .def_static("getAnyAvailableDevice", [](){ return DeviceBase::getAnyAvailableDevice(); }, DOC(dai, DeviceBase, getAnyAvailableDevice, 2)) + .def_static("getFirstAvailableDevice", &DeviceBase::getFirstAvailableDevice, DOC(dai, DeviceBase, getFirstAvailableDevice)) + .def_static("getAllAvailableDevices", &DeviceBase::getAllAvailableDevices, DOC(dai, DeviceBase, getAllAvailableDevices)) + .def_static("getEmbeddedDeviceBinary", &DeviceBase::getEmbeddedDeviceBinary, py::arg("usb2Mode"), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, DeviceBase, getEmbeddedDeviceBinary)) + .def_static("getDeviceByMxId", &DeviceBase::getDeviceByMxId, py::arg("mxId"), DOC(dai, DeviceBase, getDeviceByMxId)) // methods // Device constructor - Pipeline - .def(py::init([](const Pipeline& pipeline){ return deviceConstructorHelper(pipeline); }), py::arg("pipeline"), DOC(dai, Device, Device)) + .def(py::init([](const Pipeline& pipeline){ return deviceConstructorHelper(pipeline); }), py::arg("pipeline"), DOC(dai, DeviceBase, DeviceBase)) .def(py::init([](const Pipeline& pipeline, bool usb2Mode){ // Blocking constructor - return deviceConstructorHelper(pipeline, std::string(""), usb2Mode); - }), py::arg("pipeline"), py::arg("usb2Mode"), DOC(dai, Device, Device, 2)) + return deviceConstructorHelper(pipeline, std::string(""), usb2Mode); + }), py::arg("pipeline"), py::arg("usb2Mode"), DOC(dai, DeviceBase, DeviceBase, 2)) .def(py::init([](const Pipeline& pipeline, const std::string& pathToCmd){ // Blocking constructor - return deviceConstructorHelper(pipeline, pathToCmd); - }), py::arg("pipeline"), py::arg("pathToCmd"), DOC(dai, Device, Device, 3)) + return deviceConstructorHelper(pipeline, pathToCmd); + }), py::arg("pipeline"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 3)) .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, bool usb2Mode){ // Non blocking constructor - return std::unique_ptr(new Device(pipeline, deviceInfo, usb2Mode)); - }), py::arg("pipeline"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 4)) + py::gil_scoped_release release; + return std::make_unique(pipeline, deviceInfo, usb2Mode); + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 5)) .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor - return std::unique_ptr(new Device(pipeline, deviceInfo, pathToCmd)); - }), py::arg("pipeline"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 5)) + py::gil_scoped_release release; + return std::make_unique(pipeline, deviceInfo, pathToCmd); + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 6)) - // Device constructor - OpenVINO version - .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Device, Device, 6)) + // DeviceBase constructor - OpenVINO version + .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, DeviceBase, DeviceBase, 8)) .def(py::init([](OpenVINO::Version version, bool usb2Mode){ // Blocking constructor - return deviceConstructorHelper(version, std::string(""), usb2Mode); - }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, Device, Device, 7)) + return deviceConstructorHelper(version, std::string(""), usb2Mode); + }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, DeviceBase, DeviceBase, 9)) .def(py::init([](OpenVINO::Version version, const std::string& pathToCmd){ // Blocking constructor - return deviceConstructorHelper(version, pathToCmd); - }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, Device, Device, 8)) + return deviceConstructorHelper(version, pathToCmd); + }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 9)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, bool usb2Mode){ // Non blocking constructor - return std::unique_ptr(new Device(version, deviceInfo, usb2Mode)); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 9)) + py::gil_scoped_release release; + return std::make_unique(version, deviceInfo, usb2Mode); + }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 11)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor - return std::unique_ptr(new Device(version, deviceInfo, pathToCmd)); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 10)) + py::gil_scoped_release release; + return std::make_unique(version, deviceInfo, pathToCmd); + }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 12)) - .def("isPipelineRunning", [](Device& d) { py::gil_scoped_release release; return d.isPipelineRunning(); }, DOC(dai, Device, isPipelineRunning)) - .def("startPipeline", [](Device& d){ + .def("isPipelineRunning", [](DeviceBase& d) { py::gil_scoped_release release; return d.isPipelineRunning(); }, DOC(dai, DeviceBase, isPipelineRunning)) + .def("startPipeline", [](DeviceBase& d){ // Issue an deprecation warning PyErr_WarnEx(PyExc_DeprecationWarning, "Device(pipeline) starts the pipeline automatically. Use Device() and startPipeline(pipeline) otherwise", 1); HEDLEY_DIAGNOSTIC_PUSH @@ -203,8 +171,56 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ py::gil_scoped_release release; d.startPipeline(); HEDLEY_DIAGNOSTIC_POP - }, DOC(dai, Device, startPipeline)) - .def("startPipeline", [](Device& d, const Pipeline& pipeline) { py::gil_scoped_release release; return d.startPipeline(pipeline); }, DOC(dai, Device, startPipeline, 2)) + }, DOC(dai, DeviceBase, startPipeline)) + .def("startPipeline", [](DeviceBase& d, const Pipeline& pipeline) { py::gil_scoped_release release; return d.startPipeline(pipeline); }, DOC(dai, DeviceBase, startPipeline, 2)) + + // Doesn't require GIL release (eg, don't do RPC or long blocking things in background) + .def("setLogOutputLevel", &DeviceBase::setLogOutputLevel, py::arg("level"), DOC(dai, DeviceBase, setLogOutputLevel)) + .def("getLogOutputLevel", &DeviceBase::getLogOutputLevel, DOC(dai, DeviceBase, getLogOutputLevel)) + + // Requires GIL release + .def("setLogLevel", [](DeviceBase& d, LogLevel l) { py::gil_scoped_release release; d.setLogLevel(l); }, py::arg("level"), DOC(dai, DeviceBase, setLogLevel)) + .def("getLogLevel", [](DeviceBase& d) { py::gil_scoped_release release; return d.getLogLevel(); }, DOC(dai, DeviceBase, getLogLevel)) + .def("setSystemInformationLoggingRate", [](DeviceBase& d, float hz) { py::gil_scoped_release release; d.setSystemInformationLoggingRate(hz); }, py::arg("rateHz"), DOC(dai, DeviceBase, setSystemInformationLoggingRate)) + .def("getSystemInformationLoggingRate", [](DeviceBase& d) { py::gil_scoped_release release; return d.getSystemInformationLoggingRate(); }, DOC(dai, DeviceBase, getSystemInformationLoggingRate)) + .def("getConnectedCameras", [](DeviceBase& d) { py::gil_scoped_release release; return d.getConnectedCameras(); }, DOC(dai, DeviceBase, getConnectedCameras)) + .def("getDdrMemoryUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getDdrMemoryUsage(); }, DOC(dai, DeviceBase, getDdrMemoryUsage)) + .def("getCmxMemoryUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getCmxMemoryUsage(); }, DOC(dai, DeviceBase, getCmxMemoryUsage)) + .def("getLeonCssHeapUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getLeonCssHeapUsage(); }, DOC(dai, DeviceBase, getLeonCssHeapUsage)) + .def("getLeonMssHeapUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getLeonMssHeapUsage(); }, DOC(dai, DeviceBase, getLeonMssHeapUsage)) + .def("getChipTemperature", [](DeviceBase& d) { py::gil_scoped_release release; return d.getChipTemperature(); }, DOC(dai, DeviceBase, getChipTemperature)) + .def("getLeonCssCpuUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getLeonCssCpuUsage(); }, DOC(dai, DeviceBase, getLeonCssCpuUsage)) + .def("getLeonMssCpuUsage", [](DeviceBase& d) { py::gil_scoped_release release; return d.getLeonMssCpuUsage(); }, DOC(dai, DeviceBase, getLeonMssCpuUsage)) + .def("addLogCallback", [](DeviceBase& d, std::function callback) { py::gil_scoped_release release; return d.addLogCallback(callback); }, py::arg("callback"), DOC(dai, DeviceBase, addLogCallback)) + .def("removeLogCallback", [](DeviceBase& d, int cbId) { py::gil_scoped_release release; return d.removeLogCallback(cbId); }, py::arg("callbackId"), DOC(dai, DeviceBase, removeLogCallback)) + .def("getUsbSpeed", [](DeviceBase& d) { py::gil_scoped_release release; return d.getUsbSpeed(); }, DOC(dai, DeviceBase, getUsbSpeed)) + .def("getDeviceInfo", [](DeviceBase& d) { py::gil_scoped_release release; return d.getDeviceInfo(); }, DOC(dai, DeviceBase, getDeviceInfo)) + .def("getMxId", [](DeviceBase& d) { py::gil_scoped_release release; return d.getMxId(); }, DOC(dai, DeviceBase, getMxId)) + .def("readCalibration", [](DeviceBase& d) { py::gil_scoped_release release; return d.readCalibration(); }, DOC(dai, DeviceBase, readCalibration)) + .def("flashCalibration", [](DeviceBase& d, CalibrationHandler calibrationDataHandler) { py::gil_scoped_release release; return d.flashCalibration(calibrationDataHandler); }, py::arg("calibrationDataHandler"), DOC(dai, DeviceBase, flashCalibration)) + ; + + + device + .def(py::init([](const Pipeline& pipeline){ return deviceConstructorHelper(pipeline); }), py::arg("pipeline"), DOC(dai, Device, Device)) + .def(py::init([](const Pipeline& pipeline, bool usb2Mode){ + // Blocking constructor + return deviceConstructorHelper(pipeline, std::string(""), usb2Mode); + }), py::arg("pipeline"), py::arg("usb2Mode"), DOC(dai, Device, Device, 2)) + .def(py::init([](const Pipeline& pipeline, const std::string& pathToCmd){ + // Blocking constructor + return deviceConstructorHelper(pipeline, pathToCmd); + }), py::arg("pipeline"), py::arg("pathToCmd"), DOC(dai, Device, Device, 3)) + .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, bool usb2Mode){ + // Non blocking constructor + py::gil_scoped_release release; + return std::make_unique(pipeline, deviceInfo, usb2Mode); + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 5)) + .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, std::string pathToCmd){ + // Non blocking constructor + py::gil_scoped_release release; + return std::make_unique(pipeline, deviceInfo, pathToCmd); + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 6)) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) @@ -224,9 +240,6 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ return deviceGetQueueEventsHelper(d, d.getOutputQueueNames(), maxNumEvents, timeout); }, py::arg("maxNumEvents") = std::numeric_limits::max(), py::arg("timeout") = std::chrono::microseconds(-1), DOC(dai, Device, getQueueEvents, 4)) - .def("readCalibration", &Device::readCalibration, DOC(dai, Device, readCalibration)) - .def("flashCalibration", &Device::flashCalibration, py::arg("calibrationDataHandler"), DOC(dai, Device, flashCalibration)) - .def("getQueueEvent", [](Device& d, const std::vector& queueNames, std::chrono::microseconds timeout) { auto events = deviceGetQueueEventsHelper(d, queueNames, std::numeric_limits::max(), timeout); if(events.empty()) return std::string(""); @@ -247,28 +260,6 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ //.def("setCallback", DeviceWrapper::wrap(&Device::setCallback), py::arg("name"), py::arg("callback")) - // Doesn't require GIL release (eg, don't do RPC or long blocking things in background) - .def("setLogOutputLevel", &Device::setLogOutputLevel, py::arg("level"), DOC(dai, Device, setLogOutputLevel)) - .def("getLogOutputLevel", &Device::getLogOutputLevel, DOC(dai, Device, getLogOutputLevel)) - - // Requires GIL release - .def("setLogLevel", [](Device& d, LogLevel l) { py::gil_scoped_release release; d.setLogLevel(l); }, py::arg("level"), DOC(dai, Device, setLogLevel)) - .def("getLogLevel", [](Device& d) { py::gil_scoped_release release; return d.getLogLevel(); }, DOC(dai, Device, getLogLevel)) - .def("setSystemInformationLoggingRate", [](Device& d, float hz) { py::gil_scoped_release release; d.setSystemInformationLoggingRate(hz); }, py::arg("rateHz"), DOC(dai, Device, setSystemInformationLoggingRate)) - .def("getSystemInformationLoggingRate", [](Device& d) { py::gil_scoped_release release; return d.getSystemInformationLoggingRate(); }, DOC(dai, Device, getSystemInformationLoggingRate)) - .def("getConnectedCameras", [](Device& d) { py::gil_scoped_release release; return d.getConnectedCameras(); }, DOC(dai, Device, getConnectedCameras)) - .def("getDdrMemoryUsage", [](Device& d) { py::gil_scoped_release release; return d.getDdrMemoryUsage(); }, DOC(dai, Device, getDdrMemoryUsage)) - .def("getCmxMemoryUsage", [](Device& d) { py::gil_scoped_release release; return d.getCmxMemoryUsage(); }, DOC(dai, Device, getCmxMemoryUsage)) - .def("getLeonCssHeapUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonCssHeapUsage(); }, DOC(dai, Device, getLeonCssHeapUsage)) - .def("getLeonMssHeapUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonMssHeapUsage(); }, DOC(dai, Device, getLeonMssHeapUsage)) - .def("getChipTemperature", [](Device& d) { py::gil_scoped_release release; return d.getChipTemperature(); }, DOC(dai, Device, getChipTemperature)) - .def("getLeonCssCpuUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonCssCpuUsage(); }, DOC(dai, Device, getLeonCssCpuUsage)) - .def("getLeonMssCpuUsage", [](Device& d) { py::gil_scoped_release release; return d.getLeonMssCpuUsage(); }, DOC(dai, Device, getLeonMssCpuUsage)) - .def("addLogCallback", [](Device& d, std::function callback) { py::gil_scoped_release release; return d.addLogCallback(callback); }, py::arg("callback"), DOC(dai, Device, addLogCallback)) - .def("removeLogCallback", [](Device& d, int cbId) { py::gil_scoped_release release; return d.removeLogCallback(cbId); }, py::arg("callbackId"), DOC(dai, Device, removeLogCallback)) - .def("getUsbSpeed", [](Device& d) { py::gil_scoped_release release; return d.getUsbSpeed(); }, DOC(dai, Device, getUsbSpeed)) - .def("getDeviceInfo", [](Device& d) { py::gil_scoped_release release; return d.getDeviceInfo(); }, DOC(dai, Device, getDeviceInfo)) - .def("getMxId", [](Device& d) { py::gil_scoped_release release; return d.getMxId(); }, DOC(dai, Device, getMxId)); ; } \ No newline at end of file From 116762ae90713b1505b8a02271e1d0bcba13131e Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 5 Aug 2021 14:26:32 +0200 Subject: [PATCH 20/35] Modified documentation entries for DeviceBase and Device --- depthai-core | 2 +- src/DeviceBindings.cpp | 18 +++++++++--------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/depthai-core b/depthai-core index 3036b2bdb..d53ab2630 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 3036b2bdb47459c2531c04c1626cc05c5c3c6741 +Subproject commit d53ab26302ac5057bc0201de380fa04d4c9cfed5 diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 296de4a78..9f96a43cc 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -134,33 +134,33 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(pipeline, deviceInfo, usb2Mode); - }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 5)) + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 6)) .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(pipeline, deviceInfo, pathToCmd); - }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 6)) + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 7)) // DeviceBase constructor - OpenVINO version - .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, DeviceBase, DeviceBase, 8)) + .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, DeviceBase, DeviceBase, 10)) .def(py::init([](OpenVINO::Version version, bool usb2Mode){ // Blocking constructor return deviceConstructorHelper(version, std::string(""), usb2Mode); - }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, DeviceBase, DeviceBase, 9)) + }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, DeviceBase, DeviceBase, 11)) .def(py::init([](OpenVINO::Version version, const std::string& pathToCmd){ // Blocking constructor return deviceConstructorHelper(version, pathToCmd); - }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 9)) + }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 12)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, bool usb2Mode){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, usb2Mode); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 11)) + }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 15)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, pathToCmd); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 12)) + }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 16)) .def("isPipelineRunning", [](DeviceBase& d) { py::gil_scoped_release release; return d.isPipelineRunning(); }, DOC(dai, DeviceBase, isPipelineRunning)) .def("startPipeline", [](DeviceBase& d){ @@ -215,12 +215,12 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(pipeline, deviceInfo, usb2Mode); - }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 5)) + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 6)) .def(py::init([](const Pipeline& pipeline, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(pipeline, deviceInfo, pathToCmd); - }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 6)) + }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 7)) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) From 2d65bcc50223e4686e38a47eb04a87385b7682ca Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 6 Aug 2021 10:32:13 +0300 Subject: [PATCH 21/35] Update examples; update core --- depthai-core | 2 +- examples/corner_detector.py | 21 ++++++++++----------- examples/feature_tracker.py | 20 ++++++++++---------- 3 files changed, 21 insertions(+), 22 deletions(-) diff --git a/depthai-core b/depthai-core index 05793690a..dcbad1433 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 05793690acf5686278be30bdf6aa0abd51f4e563 +Subproject commit dcbad1433684c3ae6897e7fab5a507157fe46e47 diff --git a/examples/corner_detector.py b/examples/corner_detector.py index 53967b9f2..69de886aa 100755 --- a/examples/corner_detector.py +++ b/examples/corner_detector.py @@ -8,17 +8,16 @@ pipeline = dai.Pipeline() # Define sources and outputs -monoLeft = pipeline.createMonoCamera() -monoRight = pipeline.createMonoCamera() -featureTrackerLeft = pipeline.createFeatureTracker() -featureTrackerRight = pipeline.createFeatureTracker() - -xoutPassthroughFrameLeft = pipeline.createXLinkOut() -xoutTrackedFeaturesLeft = pipeline.createXLinkOut() -xoutPassthroughFrameRight = pipeline.createXLinkOut() -xoutTrackedFeaturesRight = pipeline.createXLinkOut() -xinTrackedFeaturesConfig = pipeline.createXLinkIn() - +monoLeft = pipeline.create(dai.node.MonoCamera) +monoRight = pipeline.create(dai.node.MonoCamera) +featureTrackerLeft = pipeline.create(dai.node.FeatureTracker) +featureTrackerRight = pipeline.create(dai.node.FeatureTracker) + +xoutPassthroughFrameLeft = pipeline.create(dai.node.XLinkOut) +xoutTrackedFeaturesLeft = pipeline.create(dai.node.XLinkOut) +xoutPassthroughFrameRight = pipeline.create(dai.node.XLinkOut) +xoutTrackedFeaturesRight = pipeline.create(dai.node.XLinkOut) +xinTrackedFeaturesConfig = pipeline.create(dai.node.XLinkIn) xoutPassthroughFrameLeft.setStreamName("passthroughFrameLeft") xoutTrackedFeaturesLeft.setStreamName("trackedFeaturesLeft") diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py index 3dce3c615..61ddf4ce7 100755 --- a/examples/feature_tracker.py +++ b/examples/feature_tracker.py @@ -75,16 +75,16 @@ def __init__(self, trackbarName, windowName): pipeline = dai.Pipeline() # Define sources and outputs -monoLeft = pipeline.createMonoCamera() -monoRight = pipeline.createMonoCamera() -featureTrackerLeft = pipeline.createFeatureTracker() -featureTrackerRight = pipeline.createFeatureTracker() - -xoutPassthroughFrameLeft = pipeline.createXLinkOut() -xoutTrackedFeaturesLeft = pipeline.createXLinkOut() -xoutPassthroughFrameRight = pipeline.createXLinkOut() -xoutTrackedFeaturesRight = pipeline.createXLinkOut() -xinTrackedFeaturesConfig = pipeline.createXLinkIn() +monoLeft = pipeline.create(dai.node.MonoCamera) +monoRight = pipeline.create(dai.node.MonoCamera) +featureTrackerLeft = pipeline.create(dai.node.FeatureTracker) +featureTrackerRight = pipeline.create(dai.node.FeatureTracker) + +xoutPassthroughFrameLeft = pipeline.create(dai.node.XLinkOut) +xoutTrackedFeaturesLeft = pipeline.create(dai.node.XLinkOut) +xoutPassthroughFrameRight = pipeline.create(dai.node.XLinkOut) +xoutTrackedFeaturesRight = pipeline.create(dai.node.XLinkOut) +xinTrackedFeaturesConfig = pipeline.create(dai.node.XLinkIn) xoutPassthroughFrameLeft.setStreamName("passthroughFrameLeft") xoutTrackedFeaturesLeft.setStreamName("trackedFeaturesLeft") From 92ee0915a9fac64f5976f5fe895373ab8595627b Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 6 Aug 2021 10:36:04 +0300 Subject: [PATCH 22/35] Add missing properties bindings --- src/pipeline/NodeBindings.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index baa8fbda5..1442aa9ea 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -459,6 +459,8 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ featureTrackerProperties .def_readwrite("initialConfig", &FeatureTrackerProperties::initialConfig, DOC(dai, FeatureTrackerProperties, initialConfig)) .def_readwrite("inputConfigSync", &FeatureTrackerProperties::inputConfigSync, DOC(dai, FeatureTrackerProperties, inputConfigSync)) + .def_readwrite("numShaves", &FeatureTrackerProperties::numShaves, DOC(dai, FeatureTrackerProperties, numShaves)) + .def_readwrite("numMemorySlices", &FeatureTrackerProperties::numMemorySlices, DOC(dai, FeatureTrackerProperties, numMemorySlices)) ; From 30221f4a0f1b455b749cebd8a046217249d04eca Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 10 Aug 2021 23:33:38 +0300 Subject: [PATCH 23/35] Update core to latest develop --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 1a17cbb43..43c2d15c4 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 1a17cbb4336d148de94180c123a4ece60e81ad85 +Subproject commit 43c2d15c4bd1429148ba2d84765b89b88bcd86f3 From d6bd4a465ffa93946b72d8f16f19eb2f124f173b Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 11 Aug 2021 16:58:17 +0300 Subject: [PATCH 24/35] Add workaround for stereo subpixel/extended mode crash at the expense of system performance --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 43c2d15c4..7b212b96c 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 43c2d15c4bd1429148ba2d84765b89b88bcd86f3 +Subproject commit 7b212b96cefe8fb36493cab28ec24eee08056e6b From bd207ce615f3295f72b55217d09d035ddb60be95 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 17 Aug 2021 17:00:20 +0300 Subject: [PATCH 25/35] Update core with bilateral fix for subpixel --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index c33c97ae7..19deade0c 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit c33c97ae7a1d72d831d29cdc0a6d4e4b2d3a6b0c +Subproject commit 19deade0cdb1834b1722e3a426ebaacd4804e6d9 From 48a76eb907f39ea3436736680de7a1c5119cad7b Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 17 Aug 2021 18:28:27 +0300 Subject: [PATCH 26/35] Pipeline: add setXlinkChunkSize --- depthai-core | 2 +- src/pipeline/PipelineBindings.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 19deade0c..ef5f3fb89 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 19deade0cdb1834b1722e3a426ebaacd4804e6d9 +Subproject commit ef5f3fb89feaa0a7a06b44ed014b205ddbf3a87a diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index f530caf8f..eb4b5fa7a 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -72,6 +72,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ .def_readwrite("pipelineVersion", &GlobalProperties::pipelineVersion) .def_readwrite("cameraTuningBlobSize", &GlobalProperties::cameraTuningBlobSize, DOC(dai, GlobalProperties, cameraTuningBlobSize)) .def_readwrite("cameraTuningBlobUri", &GlobalProperties::cameraTuningBlobUri, DOC(dai, GlobalProperties, cameraTuningBlobUri)) + .def_readwrite("xlinkChunkSize", &GlobalProperties::xlinkChunkSize, DOC(dai, GlobalProperties, xlinkChunkSize)) ; // bind pipeline @@ -95,6 +96,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ .def("setOpenVINOVersion", &Pipeline::setOpenVINOVersion, py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Pipeline, setOpenVINOVersion)) .def("getOpenVINOVersion", &Pipeline::getOpenVINOVersion, DOC(dai, Pipeline, getOpenVINOVersion)) .def("setCameraTuningBlobPath", &Pipeline::setCameraTuningBlobPath, py::arg("path"), DOC(dai, Pipeline, setCameraTuningBlobPath)) + .def("setXlinkChunkSize", &Pipeline::setXlinkChunkSize, py::arg("sizeBytes"), DOC(dai, Pipeline, setXlinkChunkSize)) .def("setCalibrationData", &Pipeline::setCalibrationData, py::arg("calibrationDataHandler"), DOC(dai, Pipeline, setCalibrationData)) .def("getCalibrationData", &Pipeline::getCalibrationData, DOC(dai, Pipeline, getCalibrationData)) // 'Template' create function From 7de407b226251102d55c36b0659c6dc351b353db Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 18 Aug 2021 06:05:42 +0300 Subject: [PATCH 27/35] Fix naming `setXlinkChunkSize` -> `setXLinkChunkSize` --- depthai-core | 2 +- src/pipeline/PipelineBindings.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index ef5f3fb89..ff58bf058 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit ef5f3fb89feaa0a7a06b44ed014b205ddbf3a87a +Subproject commit ff58bf05829efeafd63ef5b2f06569ab24ba4ce2 diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index eb4b5fa7a..d0ce5af3b 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -96,7 +96,7 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ .def("setOpenVINOVersion", &Pipeline::setOpenVINOVersion, py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Pipeline, setOpenVINOVersion)) .def("getOpenVINOVersion", &Pipeline::getOpenVINOVersion, DOC(dai, Pipeline, getOpenVINOVersion)) .def("setCameraTuningBlobPath", &Pipeline::setCameraTuningBlobPath, py::arg("path"), DOC(dai, Pipeline, setCameraTuningBlobPath)) - .def("setXlinkChunkSize", &Pipeline::setXlinkChunkSize, py::arg("sizeBytes"), DOC(dai, Pipeline, setXlinkChunkSize)) + .def("setXLinkChunkSize", &Pipeline::setXLinkChunkSize, py::arg("sizeBytes"), DOC(dai, Pipeline, setXLinkChunkSize)) .def("setCalibrationData", &Pipeline::setCalibrationData, py::arg("calibrationDataHandler"), DOC(dai, Pipeline, setCalibrationData)) .def("getCalibrationData", &Pipeline::getCalibrationData, DOC(dai, Pipeline, getCalibrationData)) // 'Template' create function From e44938b1f9ffea24a87750732b05d3efe21dcca2 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 23 Aug 2021 18:31:10 +0300 Subject: [PATCH 28/35] DeviceBindings: add `{set/get}XLinkChunkSize` RPC calls --- depthai-core | 2 +- src/DeviceBindings.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index ff58bf058..0abc44fe0 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit ff58bf05829efeafd63ef5b2f06569ab24ba4ce2 +Subproject commit 0abc44fe007549292e46b35f0c45953d7b1a3d53 diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 9f96a43cc..7daf4fd8e 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -198,6 +198,8 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ .def("getMxId", [](DeviceBase& d) { py::gil_scoped_release release; return d.getMxId(); }, DOC(dai, DeviceBase, getMxId)) .def("readCalibration", [](DeviceBase& d) { py::gil_scoped_release release; return d.readCalibration(); }, DOC(dai, DeviceBase, readCalibration)) .def("flashCalibration", [](DeviceBase& d, CalibrationHandler calibrationDataHandler) { py::gil_scoped_release release; return d.flashCalibration(calibrationDataHandler); }, py::arg("calibrationDataHandler"), DOC(dai, DeviceBase, flashCalibration)) + .def("setXLinkChunkSize", [](DeviceBase& d, int s) { py::gil_scoped_release release; d.setXLinkChunkSize(s); }, py::arg("sizeBytes"), DOC(dai, DeviceBase, setXLinkChunkSize)) + .def("getXLinkChunkSize", [](DeviceBase& d) { py::gil_scoped_release release; return d.getXLinkChunkSize(); }, DOC(dai, DeviceBase, getXLinkChunkSize)) ; From 8b80c996846127f8976724e2469e92dabe3281cb Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 23 Aug 2021 18:44:16 +0300 Subject: [PATCH 29/35] Add some missing Device() constructor overloads - no-pipeline versions --- src/DeviceBindings.cpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 7daf4fd8e..520905382 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -224,6 +224,27 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ return std::make_unique(pipeline, deviceInfo, pathToCmd); }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 7)) + // Device constructor - OpenVINO version + .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Device, Device, 10)) + .def(py::init([](OpenVINO::Version version, bool usb2Mode){ + // Blocking constructor + return deviceConstructorHelper(version, std::string(""), usb2Mode); + }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, Device, Device, 11)) + .def(py::init([](OpenVINO::Version version, const std::string& pathToCmd){ + // Blocking constructor + return deviceConstructorHelper(version, pathToCmd); + }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, Device, Device, 12)) + .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, bool usb2Mode){ + // Non blocking constructor + py::gil_scoped_release release; + return std::make_unique(version, deviceInfo, usb2Mode); + }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 15)) + .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ + // Non blocking constructor + py::gil_scoped_release release; + return std::make_unique(version, deviceInfo, pathToCmd); + }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 16)) + .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) .def("getOutputQueueNames", &Device::getOutputQueueNames, DOC(dai, Device, getOutputQueueNames)) From 9faa1d583db8ea6c67544ba7bd806b21f2f22576 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 23 Aug 2021 18:46:22 +0300 Subject: [PATCH 30/35] Device(): rename param for consistency: `deviceDesc` -> `devInfo` --- src/DeviceBindings.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 520905382..e569bd5da 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -155,12 +155,12 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, usb2Mode); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 15)) + }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 15)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, pathToCmd); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 16)) + }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 16)) .def("isPipelineRunning", [](DeviceBase& d) { py::gil_scoped_release release; return d.isPipelineRunning(); }, DOC(dai, DeviceBase, isPipelineRunning)) .def("startPipeline", [](DeviceBase& d){ @@ -238,12 +238,12 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, usb2Mode); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 15)) + }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 15)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, pathToCmd); - }), py::arg("version"), py::arg("deviceDesc"), py::arg("pathToCmd"), DOC(dai, Device, Device, 16)) + }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 16)) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) From 8a5c50d3d65f495b066e0c6cc4ca64faa21bf501 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=81ukasz=20Pi=C5=82atowski?= Date: Tue, 24 Aug 2021 09:46:24 +0200 Subject: [PATCH 31/35] Add python version and platform checks before installing requirements (#349) * Add python version and platform checks before installing requirements * adjust error text --- examples/install_requirements.py | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/examples/install_requirements.py b/examples/install_requirements.py index 9097d3ae3..8b5efb445 100755 --- a/examples/install_requirements.py +++ b/examples/install_requirements.py @@ -1,4 +1,5 @@ #!/usr/bin/env python3 +import platform import sys, os, subprocess import argparse import re @@ -45,7 +46,29 @@ def hasWhitespace(string): # Check if in virtual environment in_venv = getattr(sys, "real_prefix", getattr(sys, "base_prefix", sys.prefix)) != sys.prefix pip_call = [sys.executable, "-m", "pip"] +pip_installed = True pip_install = pip_call + ["install"] + +try: + subprocess.check_call(pip_call + ["--version"]) +except subprocess.CalledProcessError as ex: + pip_installed = False + +if not pip_installed: + err_str = "Issues with \"pip\" package detected! Follow the official instructions to install - https://pip.pypa.io/en/stable/installation/" + raise RuntimeError(err_str) + +if sys.version_info[0] != 3: + raise RuntimeError("Examples require Python 3 to run (detected: Python {})".format(sys.version_info[0])) + +if platform.machine() == "arm64" and platform.system() == "Darwin": + err_str = "There are no prebuilt wheels for M1 processors. Please open the following link for a solution - https://discuss.luxonis.com/d/69-running-depthai-on-apple-m1-based-macs" + raise RuntimeError(err_str) + +is_pi = platform.machine().startswith("arm") or platform.machine().startswith("aarch") +if is_pi and sys.version_info[1] in (7, 9): + print("[WARNING] There are no prebuilt wheels for Python 3.{} for OpenCV, building process on this device may be long and unstable".format(sys.version_info[1])) + if not in_venv: pip_install.append("--user") From 23fb52a95fff4f72da0d8d123784c819de0cc473 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 24 Aug 2021 16:48:32 +0300 Subject: [PATCH 32/35] Remove for now docstrings for some Device() constructors, as not available (not present in generated/depthai_python_docstring.hpp). Update core after merge --- depthai-core | 2 +- src/DeviceBindings.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/depthai-core b/depthai-core index 0abc44fe0..1a6d7da14 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 0abc44fe007549292e46b35f0c45953d7b1a3d53 +Subproject commit 1a6d7da14eccff06c7d27e0457b7cfc50e7aede2 diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index e569bd5da..f24809133 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -225,25 +225,25 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 7)) // Device constructor - OpenVINO version - .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, Device, Device, 10)) + .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION) .def(py::init([](OpenVINO::Version version, bool usb2Mode){ // Blocking constructor return deviceConstructorHelper(version, std::string(""), usb2Mode); - }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, Device, Device, 11)) + }), py::arg("version"), py::arg("usb2Mode")) .def(py::init([](OpenVINO::Version version, const std::string& pathToCmd){ // Blocking constructor return deviceConstructorHelper(version, pathToCmd); - }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, Device, Device, 12)) + }), py::arg("version"), py::arg("pathToCmd")) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, bool usb2Mode){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, usb2Mode); - }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, Device, Device, 15)) + }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, pathToCmd); - }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 16)) + }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd")) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) From dd6f40d6a35c2fe01fc2e5d07cb56120c12ffc38 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 24 Aug 2021 17:32:14 +0300 Subject: [PATCH 33/35] Add back docstrings pointing to DeviceBase --- src/DeviceBindings.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index f24809133..4e4a7269f 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -225,25 +225,25 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ }), py::arg("pipeline"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, Device, Device, 7)) // Device constructor - OpenVINO version - .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION) + .def(py::init([](OpenVINO::Version version){ return deviceConstructorHelper(version); }), py::arg("version") = Pipeline::DEFAULT_OPENVINO_VERSION, DOC(dai, DeviceBase, DeviceBase, 10)) .def(py::init([](OpenVINO::Version version, bool usb2Mode){ // Blocking constructor return deviceConstructorHelper(version, std::string(""), usb2Mode); - }), py::arg("version"), py::arg("usb2Mode")) + }), py::arg("version"), py::arg("usb2Mode"), DOC(dai, DeviceBase, DeviceBase, 11)) .def(py::init([](OpenVINO::Version version, const std::string& pathToCmd){ // Blocking constructor return deviceConstructorHelper(version, pathToCmd); - }), py::arg("version"), py::arg("pathToCmd")) + }), py::arg("version"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 12)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, bool usb2Mode){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, usb2Mode); - }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false) + }), py::arg("version"), py::arg("devInfo"), py::arg("usb2Mode") = false, DOC(dai, DeviceBase, DeviceBase, 15)) .def(py::init([](OpenVINO::Version version, const DeviceInfo& deviceInfo, std::string pathToCmd){ // Non blocking constructor py::gil_scoped_release release; return std::make_unique(version, deviceInfo, pathToCmd); - }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd")) + }), py::arg("version"), py::arg("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 16)) .def("getOutputQueue", static_cast(Device::*)(const std::string&)>(&Device::getOutputQueue), py::arg("name"), DOC(dai, Device, getOutputQueue)) .def("getOutputQueue", static_cast(Device::*)(const std::string&, unsigned int, bool)>(&Device::getOutputQueue), py::arg("name"), py::arg("maxSize"), py::arg("blocking") = true, DOC(dai, Device, getOutputQueue, 2)) From b555f0583bcbd83e870b5043c95673b6a42efc88 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 24 Aug 2021 18:05:09 +0300 Subject: [PATCH 34/35] Update core --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 1a6d7da14..1f2655721 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 1a6d7da14eccff06c7d27e0457b7cfc50e7aede2 +Subproject commit 1f265572171b4baa77a4b8e202db96195e3302af From 9b24e446b75aa4f60ba28fb9d64db1a7f617714f Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 24 Aug 2021 18:32:29 +0300 Subject: [PATCH 35/35] Bump version to 2.10.0.0 --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 1f2655721..120407672 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 1f265572171b4baa77a4b8e202db96195e3302af +Subproject commit 12040767262f3d3d0ce796cfc80a69d1b2dff921