diff --git a/depthai-core b/depthai-core index 661f28943..120407672 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 661f28943cb2e25dbe81003d4cec1f87b3319d31 +Subproject commit 12040767262f3d3d0ce796cfc80a69d1b2dff921 diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index dd2ec34a6..ef7b7f833 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -127,3 +127,5 @@ 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(script_camera_control script_camera_control.py) +add_python_example(feature_tracker feature_tracker.py) +add_python_example(corner_detector corner_detector.py) diff --git a/examples/corner_detector.py b/examples/corner_detector.py new file mode 100755 index 000000000..69de886aa --- /dev/null +++ b/examples/corner_detector.py @@ -0,0 +1,105 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai + + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +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") +xoutPassthroughFrameRight.setStreamName("passthroughFrameRight") +xoutTrackedFeaturesRight.setStreamName("trackedFeaturesRight") +xinTrackedFeaturesConfig.setStreamName("trackedFeaturesConfig") + +# Properties +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) +monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) +monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) + +# Disable optical flow +featureTrackerLeft.initialConfig.setMotionEstimator(False) +featureTrackerRight.initialConfig.setMotionEstimator(False) + +# Linking +monoLeft.out.link(featureTrackerLeft.inputImage) +featureTrackerLeft.passthroughInputImage.link(xoutPassthroughFrameLeft.input) +featureTrackerLeft.outputFeatures.link(xoutTrackedFeaturesLeft.input) +xinTrackedFeaturesConfig.out.link(featureTrackerLeft.inputConfig) + +monoRight.out.link(featureTrackerRight.inputImage) +featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) +featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) +xinTrackedFeaturesConfig.out.link(featureTrackerRight.inputConfig) + +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" + + 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() + 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 + drawFeatures(leftFrame, trackedFeaturesLeft) + + trackedFeaturesRight = outputFeaturesRightQueue.get().trackedFeatures + drawFeatures(rightFrame, trackedFeaturesRight) + + # 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.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.FeatureTrackerConfig.CornerDetector.Type.HARRIS + print("Switching to Harris") + + cfg = dai.FeatureTrackerConfig() + cfg.set(featureTrackerConfig) + inputFeatureTrackerConfigQueue.send(cfg) diff --git a/examples/feature_tracker.py b/examples/feature_tracker.py new file mode 100755 index 000000000..61ddf4ce7 --- /dev/null +++ b/examples/feature_tracker.py @@ -0,0 +1,173 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai +from collections import deque + +class FeatureTrackerDrawer: + + 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): + FeatureTrackerDrawer.trackedFeaturesPathLength = val + pass + + def trackFeaturePath(self, features): + + newTrackedIDs = set() + for currentFeature in features: + currentID = currentFeature.id + newTrackedIDs.add(currentID) + + if currentID not in self.trackedFeaturesPath: + self.trackedFeaturesPath[currentID] = deque() + + path = self.trackedFeaturesPath[currentID] + + path.append(currentFeature.position) + while(len(path) > max(1, FeatureTrackerDrawer.trackedFeaturesPathLength)): + path.popleft() + + self.trackedFeaturesPath[currentID] = path + + featuresToRemove = set() + for oldId in self.trackedIDs: + if oldId not in newTrackedIDs: + featuresToRemove.add(oldId) + + for id in featuresToRemove: + self.trackedFeaturesPath.pop(id) + + self.trackedIDs = newTrackedIDs + + def drawFeatures(self, img): + + cv2.setTrackbarPos(self.trackbarName, self.windowName, FeatureTrackerDrawer.trackedFeaturesPathLength) + + for featurePath in self.trackedFeaturesPath.values(): + path = featurePath + + 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): + self.trackbarName = trackbarName + self.windowName = windowName + cv2.namedWindow(windowName) + cv2.createTrackbar(trackbarName, windowName, FeatureTrackerDrawer.trackedFeaturesPathLength, FeatureTrackerDrawer.maxTrackedFeaturesPathLength, self.onTrackBar) + self.trackedIDs = set() + self.trackedFeaturesPath = dict() + + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +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") +xoutPassthroughFrameRight.setStreamName("passthroughFrameRight") +xoutTrackedFeaturesRight.setStreamName("trackedFeaturesRight") +xinTrackedFeaturesConfig.setStreamName("trackedFeaturesConfig") + +# Properties +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) +monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_720_P) +monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) + +# Linking +monoLeft.out.link(featureTrackerLeft.inputImage) +featureTrackerLeft.passthroughInputImage.link(xoutPassthroughFrameLeft.input) +featureTrackerLeft.outputFeatures.link(xoutTrackedFeaturesLeft.input) +xinTrackedFeaturesConfig.out.link(featureTrackerLeft.inputConfig) + +monoRight.out.link(featureTrackerRight.inputImage) +featureTrackerRight.passthroughInputImage.link(xoutPassthroughFrameRight.input) +featureTrackerRight.outputFeatures.link(xoutTrackedFeaturesRight.input) +xinTrackedFeaturesConfig.out.link(featureTrackerRight.inputConfig) + +# By default the least mount of resources are allocated +# increasing it improves performance +numShaves = 2 +numMemorySlices = 2 +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: + + # 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" + leftFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", leftWindowName) + + rightWindowName = "right" + rightFeatureDrawer = FeatureTrackerDrawer("Feature tracking duration (frames)", rightWindowName) + + 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 + leftFeatureDrawer.trackFeaturePath(trackedFeaturesLeft) + leftFeatureDrawer.drawFeatures(leftFrame) + + trackedFeaturesRight = outputFeaturesRightQueue.get().trackedFeatures + rightFeatureDrawer.trackFeaturePath(trackedFeaturesRight) + rightFeatureDrawer.drawFeatures(rightFrame) + + # 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.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.FeatureTrackerConfig.MotionEstimator.Type.LUCAS_KANADE_OPTICAL_FLOW + print("Switching to Lucas-Kanade optical flow") + + cfg = dai.FeatureTrackerConfig() + cfg.set(featureTrackerConfig) + inputFeatureTrackerConfigQueue.send(cfg) 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") diff --git a/src/DatatypeBindings.cpp b/src/DatatypeBindings.cpp index 894ff8f9a..12c82c307 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/TrackedFeatures.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 @@ -107,6 +110,19 @@ 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_ 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)); /////////////////////////////////////////////////////////////////////// @@ -978,6 +994,8 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ 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) @@ -1042,4 +1060,116 @@ void DatatypeBindings::bind(pybind11::module& m, void* pCallstack){ .def("getConfigData", &EdgeDetectorConfig::getConfigData, DOC(dai, EdgeDetectorConfig, getConfigData)) ; + // Bind RawTrackedFeatures + rawTrackedFeatures + .def(py::init<>()) + .def_readwrite("trackedFeatures", &RawTrackedFeatures::trackedFeatures) + ; + + trackedFeature + .def(py::init<>()) + .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 + ; + + + + rawFeatureTrackerConfig + .def(py::init<>()) + .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", RawFeatureTrackerConfig::CornerDetector::Type::HARRIS) + .value("SHI_THOMASI", RawFeatureTrackerConfig::CornerDetector::Type::SHI_THOMASI) + ; + + cornerDetectorThresholds + .def(py::init<>()) + .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", &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", RawFeatureTrackerConfig::MotionEstimator::Type::LUCAS_KANADE_OPTICAL_FLOW) + .value("HW_MOTION_ESTIMATION", RawFeatureTrackerConfig::MotionEstimator::Type::HW_MOTION_ESTIMATION) + ; + + motionEstimatorOpticalFlow + .def(py::init<>()) + .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", &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", &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)) + ; + + + // Bind TrackedFeatures + py::class_>(m, "TrackedFeatures", DOC(dai, TrackedFeatures)) + .def(py::init<>()) + .def_property("trackedFeatures", [](TrackedFeatures& feat) { return &feat.trackedFeatures; }, [](TrackedFeatures& feat, std::vector val) { feat.trackedFeatures = val; }, DOC(dai, TrackedFeatures, trackedFeatures)) + ; + + // 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)) + .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("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"); + m.attr("FeatureTrackerConfig").attr("FeatureMaintainer") = m.attr("RawFeatureTrackerConfig").attr("FeatureMaintainer"); + } diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 3f242a698..4e4a7269f 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, 6)) .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, 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, 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, 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, 7)) + return deviceConstructorHelper(version, std::string(""), 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"), DOC(dai, Device, Device, 8)) + return deviceConstructorHelper(version, 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 - 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("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 - 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("devInfo"), py::arg("pathToCmd"), DOC(dai, DeviceBase, DeviceBase, 16)) - .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,79 @@ 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)) + .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)) + ; + + + 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, 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, 7)) + + // Device constructor - 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"), 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, 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, 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"), 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)) @@ -224,9 +263,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 +283,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 diff --git a/src/pipeline/NodeBindings.cpp b/src/pipeline/NodeBindings.cpp index b54ed085a..5566d3775 100644 --- a/src/pipeline/NodeBindings.cpp +++ b/src/pipeline/NodeBindings.cpp @@ -21,6 +21,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" @@ -173,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"); @@ -211,6 +213,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); @@ -463,6 +466,15 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ ; + // FeatureTracker properties + 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)) + ; + + //////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////// // Node Bindings after properties, so types are resolved @@ -1026,5 +1038,18 @@ void NodeBindings::bind(pybind11::module& m, void* pCallstack){ daiNodeModule.attr("EdgeDetector").attr("Properties") = edgeDetectorProperties; + // FeatureTracker 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)) + .def("setHardwareResources", &FeatureTracker::setHardwareResources, py::arg("numShaves"), py::arg("numMemorySlices"), DOC(dai, node, FeatureTracker, setHardwareResources)) + ; + daiNodeModule.attr("FeatureTracker").attr("Properties") = featureTrackerProperties; + + } diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 4583bf9ab..d0ce5af3b 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -24,6 +24,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" @@ -71,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 @@ -94,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 @@ -125,6 +128,8 @@ void PipelineBindings::bind(pybind11::module& m, void* pCallstack){ .def("createObjectTracker", &Pipeline::create) .def("createIMU", &Pipeline::create) .def("createEdgeDetector", &Pipeline::create) + .def("createFeatureTracker", &Pipeline::create) + ;