From 87a13df50d101d08b9f47f93dd34c9fb83c269f0 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 25 Oct 2022 19:02:17 +0300 Subject: [PATCH 01/43] FW: OV9282 720p/800p max FPS: 60 -> 120 --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index c87740908..3ecbb1e8f 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit c87740908330100112bf12ea7f5aaf016fda89b2 +Subproject commit 3ecbb1e8f28f1b2e1a1e227b735526afabd87c05 From dc88bcd4d49e57f3524554b9703da27129b5fba3 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 8 Nov 2022 14:15:12 +0100 Subject: [PATCH 02/43] Added device side trace logging --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 0ba40d0f8..d38eb3bda 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 0ba40d0f8837d642c16c8d2b941df5aa92235563 +Subproject commit d38eb3bda395b7161cbfd094c8c5afccf1e149c5 From 2bdf25bc919a550e79d6bb993a62ea1dc44f2527 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 18 Nov 2022 00:08:54 +0100 Subject: [PATCH 03/43] Added EepromError exception class --- depthai-core | 2 +- src/DeviceBindings.cpp | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index a78ea3bac..e2445c648 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit a78ea3bac1695254c02b5ee066ba3c3312b8367e +Subproject commit e2445c648643224735e35218050bb1cc4c95544a diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index f001781d5..43efada81 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -2,6 +2,7 @@ // depthai #include "depthai/device/Device.hpp" +#include "depthai/device/EepromError.hpp" #include "depthai/pipeline/Pipeline.hpp" #include "depthai/utility/Clock.hpp" #include "depthai/xlink/XLinkConnection.hpp" @@ -328,6 +329,13 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ py::bind_map_patched>(boardConfig, "UARTMap"); + // pybind11 limitation of having actual classes as exceptions + // Possible but requires a larger workaround + // https://stackoverflow.com/questions/62087383/how-can-you-bind-exceptions-with-custom-fields-and-constructors-in-pybind11-and + + // Bind EepromError + auto eepromError = py::register_exception(m, "EepromError", PyExc_RuntimeError); + /////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////// From 4077fe0b2574be038f33af3d31e4810d6e82e71a Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 18 Nov 2022 00:09:14 +0100 Subject: [PATCH 04/43] Increased limit on DeviceBootloader monitor timeout --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index e2445c648..f4f5907bb 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit e2445c648643224735e35218050bb1cc4c95544a +Subproject commit f4f5907bb0c57e4c1634cb247d4856f80a488ec7 From 454d1e7d5080d868d4b9335c2b3e08a93d19c80b Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 29 Nov 2022 15:06:21 +0100 Subject: [PATCH 05/43] Added camera naming capabilites, setting and retrieving. WIP: rest of devices --- depthai-core | 2 +- examples/ColorCamera/rgb_preview.py | 1 + src/pipeline/CommonBindings.cpp | 9 +++++++++ src/pipeline/node/ColorCameraBindings.cpp | 2 ++ src/pipeline/node/MonoCameraBindings.cpp | 3 ++- 5 files changed, 15 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index f4f5907bb..f19cd677c 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit f4f5907bb0c57e4c1634cb247d4856f80a488ec7 +Subproject commit f19cd677cd768a564f93ea55e30b72ce35dd9558 diff --git a/examples/ColorCamera/rgb_preview.py b/examples/ColorCamera/rgb_preview.py index a07e464df..81c1d8460 100755 --- a/examples/ColorCamera/rgb_preview.py +++ b/examples/ColorCamera/rgb_preview.py @@ -31,6 +31,7 @@ print('Bootloader version:', device.getBootloaderVersion()) # Device name print('Device name:', device.getDeviceName()) + print('Cameras: ', device.getConnectedCameraFeatures()) # Output queue will be used to get the rgb frames from the output defined above qRgb = device.getOutputQueue(name="rgb", maxSize=4, blocking=False) diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 952014582..2f8c346bc 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -20,6 +20,9 @@ #include "depthai-shared/common/RotatedRect.hpp" #include "depthai-shared/common/Rect.hpp" +// depthai +#include "depthai/common/CameraFeatures.hpp" + void CommonBindings::bind(pybind11::module& m, void* pCallstack){ using namespace dai; @@ -162,6 +165,12 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ .def_readwrite("orientation", &CameraFeatures::orientation) .def_readwrite("supportedTypes", &CameraFeatures::supportedTypes) .def_readwrite("hasAutofocus", &CameraFeatures::hasAutofocus) + .def_readwrite("name", &CameraFeatures::name) + .def("__repr__", [](CameraFeatures& camera) { + std::stringstream stream; + stream << camera; + return stream.str(); + }); ; // MemoryInfo diff --git a/src/pipeline/node/ColorCameraBindings.cpp b/src/pipeline/node/ColorCameraBindings.cpp index e1e8eb060..48956281f 100644 --- a/src/pipeline/node/ColorCameraBindings.cpp +++ b/src/pipeline/node/ColorCameraBindings.cpp @@ -180,6 +180,8 @@ void bind_colorcamera(pybind11::module& m, void* pCallstack){ .def("getStillNumFramesPool", &ColorCamera::getStillNumFramesPool, DOC(dai, node, ColorCamera, getStillNumFramesPool)) .def("getRawNumFramesPool", &ColorCamera::getRawNumFramesPool, DOC(dai, node, ColorCamera, getRawNumFramesPool)) .def("getIspNumFramesPool", &ColorCamera::getIspNumFramesPool, DOC(dai, node, ColorCamera, getIspNumFramesPool)) + .def("setCamera", &ColorCamera::setCamera, py::arg("name"), DOC(dai, node, ColorCamera, setCamera)) + .def("getCamera", &ColorCamera::getCamera, DOC(dai, node, ColorCamera, getCamera)) ; // ALIAS daiNodeModule.attr("ColorCamera").attr("Properties") = colorCameraProperties; diff --git a/src/pipeline/node/MonoCameraBindings.cpp b/src/pipeline/node/MonoCameraBindings.cpp index ecd3abfe7..b25acaf6d 100644 --- a/src/pipeline/node/MonoCameraBindings.cpp +++ b/src/pipeline/node/MonoCameraBindings.cpp @@ -85,7 +85,8 @@ void bind_monocamera(pybind11::module& m, void* pCallstack){ .def("getNumFramesPool", &MonoCamera::getNumFramesPool, DOC(dai, node, MonoCamera, getNumFramesPool)) .def("setRawNumFramesPool", &MonoCamera::setRawNumFramesPool, DOC(dai, node, MonoCamera, setRawNumFramesPool)) .def("getRawNumFramesPool", &MonoCamera::getRawNumFramesPool, DOC(dai, node, MonoCamera, getRawNumFramesPool)) - + .def("setCamera", &MonoCamera::setCamera, py::arg("name"), DOC(dai, node, MonoCamera, setCamera)) + .def("getCamera", &MonoCamera::getCamera, DOC(dai, node, MonoCamera, getCamera)) ; // ALIAS daiNodeModule.attr("MonoCamera").attr("Properties") = monoCameraProperties; From 3a784d434e1c35820354035cf377812a8b1d161b Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 29 Nov 2022 20:20:14 +0200 Subject: [PATCH 06/43] FW/CameraControl: fix still-capture for sockets other than RGB/center --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index f4f5907bb..61c1e0fec 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit f4f5907bb0c57e4c1634cb247d4856f80a488ec7 +Subproject commit 61c1e0fec51586af85b2317eb91884e5ba6b7c70 From ba9bdfb7d66e0767b8199a8f7b08c54e3193e30b Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 1 Dec 2022 17:37:42 +0100 Subject: [PATCH 07/43] [FW] Fixed ImageManip + Subpixel issues and added FFC camera naming --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index d1661bf74..48f0214fa 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit d1661bf74cf3afe8b42370c00955f3033dcd7f30 +Subproject commit 48f0214fa6c50b10dd1982ddaf014803cf088645 From fa263a8edeac5878e18aea57ad580466c7deb9b6 Mon Sep 17 00:00:00 2001 From: Matevz Morato Date: Mon, 12 Dec 2022 20:01:54 +0100 Subject: [PATCH 08/43] Update core --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 48f0214fa..c95a06aac 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 48f0214fa6c50b10dd1982ddaf014803cf088645 +Subproject commit c95a06aac4b51bc062bed390ec83f5377fdea337 From d5b09fa3db477d2b7ec7644c326e840656e48f08 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Mon, 12 Dec 2022 21:34:42 +0100 Subject: [PATCH 09/43] WIP: Camera node --- .gitignore | 1 + CMakeLists.txt | 1 + depthai-core | 2 +- examples/Camera/camera_rgb_preview.py | 46 +++++++ src/DeviceBindings.cpp | 2 +- src/pipeline/PipelineBindings.cpp | 1 + src/pipeline/node/CameraBindings.cpp | 189 ++++++++++++++++++++++++++ src/pipeline/node/NodeBindings.cpp | 2 + 8 files changed, 242 insertions(+), 2 deletions(-) create mode 100755 examples/Camera/camera_rgb_preview.py create mode 100644 src/pipeline/node/CameraBindings.cpp diff --git a/.gitignore b/.gitignore index c6d3c5cc3..98f9cb60a 100644 --- a/.gitignore +++ b/.gitignore @@ -38,6 +38,7 @@ wheelhouse/ .venv env/ venv/ +venv_*/ ENV/ env.bak/ venv.bak/ diff --git a/CMakeLists.txt b/CMakeLists.txt index 50c01aa89..2183df54f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -107,6 +107,7 @@ pybind11_add_module(${TARGET_NAME} src/pipeline/node/XLinkInBindings.cpp src/pipeline/node/XLinkOutBindings.cpp src/pipeline/node/ColorCameraBindings.cpp + src/pipeline/node/CameraBindings.cpp src/pipeline/node/MonoCameraBindings.cpp src/pipeline/node/StereoDepthBindings.cpp src/pipeline/node/NeuralNetworkBindings.cpp diff --git a/depthai-core b/depthai-core index 48f0214fa..80eefc8a8 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 48f0214fa6c50b10dd1982ddaf014803cf088645 +Subproject commit 80eefc8a893628aca59315753ca74d1b32019809 diff --git a/examples/Camera/camera_rgb_preview.py b/examples/Camera/camera_rgb_preview.py new file mode 100755 index 000000000..8960651d0 --- /dev/null +++ b/examples/Camera/camera_rgb_preview.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai + +# Create pipeline +pipeline = dai.Pipeline() + +# Define source and output +cam = pipeline.create(dai.node.Camera) +xoutRgb = pipeline.create(dai.node.XLinkOut) + +xoutRgb.setStreamName("camera") + +# Properties +cam.setPreviewSize(300, 300) +cam.setInterleaved(False) +cam.setColorOrder(dai.CameraProperties.ColorOrder.RGB) +cam.setBoardSocket(dai.CameraBoardSocket.LEFT) + +# Linking +cam.isp.link(xoutRgb.input) + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + print('Connected cameras:', device.getConnectedCameraFeatures()) + # Print out usb speed + print('Usb speed:', device.getUsbSpeed().name) + # Bootloader version + if device.getBootloaderVersion() is not None: + print('Bootloader version:', device.getBootloaderVersion()) + # Device name + print('Device name:', device.getDeviceName()) + + # Output queue will be used to get the rgb frames from the output defined above + qRgb = device.getOutputQueue(name="camera", maxSize=4, blocking=False) + + while True: + inRgb = qRgb.get() # blocking call, will wait until a new data has arrived + + # Retrieve 'bgr' (opencv format) frame + cv2.imshow("camera", inRgb.getCvFrame()) + + if cv2.waitKey(1) == ord('q'): + break diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 43efada81..4e0cb6be8 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -544,7 +544,7 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ .def("flashFactoryEepromClear", [](DeviceBase& d) { py::gil_scoped_release release; d.flashFactoryEepromClear(); }, DOC(dai, DeviceBase, flashFactoryEepromClear)) .def("setTimesync", [](DeviceBase& d, std::chrono::milliseconds p, int s, bool r) { py::gil_scoped_release release; return d.setTimesync(p,s,r); }, DOC(dai, DeviceBase, setTimesync)) .def("setTimesync", [](DeviceBase& d, bool e) { py::gil_scoped_release release; return d.setTimesync(e); }, py::arg("enable"), DOC(dai, DeviceBase, setTimesync, 2)) - .def("getDeviceName", [](DeviceBase& d) { py::gil_scoped_release release; return d.getDeviceName(); }, DOC(dai, DeviceBase, getDeviceName)) + .def("getDeviceName", [](DeviceBase& d) { std::string name; { py::gil_scoped_release release; name = d.getDeviceName(); } return py::bytes(name).attr("decode")("utf-8", "replace"); }, DOC(dai, DeviceBase, getDeviceName)) ; diff --git a/src/pipeline/PipelineBindings.cpp b/src/pipeline/PipelineBindings.cpp index 22ea646dd..cfdd9f588 100644 --- a/src/pipeline/PipelineBindings.cpp +++ b/src/pipeline/PipelineBindings.cpp @@ -10,6 +10,7 @@ #include "depthai/pipeline/node/XLinkOut.hpp" #include "depthai/pipeline/node/NeuralNetwork.hpp" #include "depthai/pipeline/node/ColorCamera.hpp" +#include "depthai/pipeline/node/Camera.hpp" #include "depthai/pipeline/node/VideoEncoder.hpp" #include "depthai/pipeline/node/SPIOut.hpp" #include "depthai/pipeline/node/SPIIn.hpp" diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp new file mode 100644 index 000000000..98624b0eb --- /dev/null +++ b/src/pipeline/node/CameraBindings.cpp @@ -0,0 +1,189 @@ +#include "NodeBindings.hpp" +#include "Common.hpp" + +#include "depthai/pipeline/Pipeline.hpp" +#include "depthai/pipeline/Node.hpp" +#include "depthai/pipeline/node/Camera.hpp" + +void bind_camera(pybind11::module& m, void* pCallstack){ + + using namespace dai; + using namespace dai::node; + + // Node and Properties declare upfront + py::class_ cameraProperties(m, "CameraProperties", DOC(dai, CameraProperties)); + // py::enum_ cameraPropertiesSensorResolution(cameraProperties, "SensorResolution", DOC(dai, CameraProperties, SensorResolution)); + py::enum_ cameraPropertiesColorOrder(cameraProperties, "ColorOrder", DOC(dai, CameraProperties, ColorOrder)); + auto camera = ADD_NODE(Camera); + + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + // Call the rest of the type defines, then perform the actual bindings + Callstack* callstack = (Callstack*) pCallstack; + auto cb = callstack->top(); + callstack->pop(); + cb(m, pCallstack); + // Actual bindings + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + /////////////////////////////////////////////////////////////////////// + + // // Camera Properties + // cameraPropertiesSensorResolution + // .value("THE_1080_P", CameraProperties::SensorResolution::THE_1080_P) + // .value("THE_1200_P", CameraProperties::SensorResolution::THE_1200_P) + // .value("THE_4_K", CameraProperties::SensorResolution::THE_4_K) + // .value("THE_5_MP", CameraProperties::SensorResolution::THE_5_MP) + // .value("THE_12_MP", CameraProperties::SensorResolution::THE_12_MP) + // .value("THE_4000X3000", CameraProperties::SensorResolution::THE_4000X3000) + // .value("THE_13_MP", CameraProperties::SensorResolution::THE_13_MP) + // .value("THE_5312X6000", CameraProperties::SensorResolution::THE_5312X6000) + // .value("THE_48_MP", CameraProperties::SensorResolution::THE_48_MP) + // .value("THE_720_P", CameraProperties::SensorResolution::THE_720_P) + // .value("THE_800_P", CameraProperties::SensorResolution::THE_800_P) + // ; + + cameraPropertiesColorOrder + .value("BGR", CameraProperties::ColorOrder::BGR) + .value("RGB", CameraProperties::ColorOrder::RGB) + ; + + cameraProperties + .def_readwrite("initialControl", &CameraProperties::initialControl) + .def_readwrite("boardSocket", &CameraProperties::boardSocket) + .def_readwrite("imageOrientation", &CameraProperties::imageOrientation) + .def_readwrite("colorOrder", &CameraProperties::colorOrder) + .def_readwrite("interleaved", &CameraProperties::interleaved) + .def_readwrite("fp16", &CameraProperties::fp16) + .def_readwrite("previewHeight", &CameraProperties::previewHeight) + .def_readwrite("previewWidth", &CameraProperties::previewWidth) + .def_readwrite("videoHeight", &CameraProperties::videoHeight) + .def_readwrite("videoWidth", &CameraProperties::videoWidth) + .def_readwrite("stillHeight", &CameraProperties::stillHeight) + .def_readwrite("stillWidth", &CameraProperties::stillWidth) + // .def_readwrite("resolution", &CameraProperties::resolution) + .def_readwrite("fps", &CameraProperties::fps) + .def_readwrite("sensorCropX", &CameraProperties::sensorCropX) + .def_readwrite("sensorCropY", &CameraProperties::sensorCropY) + .def_readwrite("previewKeepAspectRatio", &CameraProperties::previewKeepAspectRatio) + .def_readwrite("ispScale", &CameraProperties::ispScale) + .def_readwrite("numFramesPoolRaw", &CameraProperties::numFramesPoolRaw) + .def_readwrite("numFramesPoolIsp", &CameraProperties::numFramesPoolIsp) + .def_readwrite("numFramesPoolVideo", &CameraProperties::numFramesPoolVideo) + .def_readwrite("numFramesPoolPreview", &CameraProperties::numFramesPoolPreview) + .def_readwrite("numFramesPoolStill", &CameraProperties::numFramesPoolStill) + ; + + // Camera node + camera + .def_readonly("inputConfig", &Camera::inputConfig, DOC(dai, node, Camera, inputConfig)) + .def_readonly("inputControl", &Camera::inputControl, DOC(dai, node, Camera, inputControl)) + .def_readonly("initialControl", &Camera::initialControl, DOC(dai, node, Camera, initialControl)) + .def_readonly("video", &Camera::video, DOC(dai, node, Camera, video)) + .def_readonly("preview", &Camera::preview, DOC(dai, node, Camera, preview)) + .def_readonly("still", &Camera::still, DOC(dai, node, Camera, still)) + .def_readonly("isp", &Camera::isp, DOC(dai, node, Camera, isp)) + .def_readonly("raw", &Camera::raw, DOC(dai, node, Camera, raw)) + .def_readonly("frameEvent", &Camera::frameEvent, DOC(dai, node, Camera, frameEvent)) + .def("setCamId", [](Camera& c, int64_t id) { + // Issue an deprecation warning + PyErr_WarnEx(PyExc_DeprecationWarning, "setCamId() is deprecated, use setBoardSocket() instead.", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + c.setCamId(id); + HEDLEY_DIAGNOSTIC_POP + }) + .def("getCamId", [](Camera& c) { + // Issue an deprecation warning + PyErr_WarnEx(PyExc_DeprecationWarning, "getCamId() is deprecated, use getBoardSocket() instead.", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + return c.getCamId(); + HEDLEY_DIAGNOSTIC_POP + }) + .def("setBoardSocket", &Camera::setBoardSocket, py::arg("boardSocket"), DOC(dai, node, Camera, setBoardSocket)) + .def("getBoardSocket", &Camera::getBoardSocket, DOC(dai, node, Camera, getBoardSocket)) + .def("setImageOrientation", &Camera::setImageOrientation, py::arg("imageOrientation"), DOC(dai, node, Camera, setImageOrientation)) + .def("getImageOrientation", &Camera::getImageOrientation, DOC(dai, node, Camera, getImageOrientation)) + .def("setColorOrder", &Camera::setColorOrder, py::arg("colorOrder"), DOC(dai, node, Camera, setColorOrder)) + .def("getColorOrder", &Camera::getColorOrder, DOC(dai, node, Camera, getColorOrder)) + .def("setInterleaved", &Camera::setInterleaved, py::arg("interleaved"), DOC(dai, node, Camera, setInterleaved)) + .def("getInterleaved", &Camera::getInterleaved, DOC(dai, node, Camera, getInterleaved)) + .def("setFp16", &Camera::setFp16, py::arg("fp16"), DOC(dai, node, Camera, setFp16)) + .def("getFp16", &Camera::getFp16, DOC(dai, node, Camera, getFp16)) + .def("setPreviewSize", static_cast(&Camera::setPreviewSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setPreviewSize)) + .def("setPreviewSize", static_cast)>(&Camera::setPreviewSize), py::arg("size"), DOC(dai, node, Camera, setPreviewSize, 2)) + .def("setVideoSize", static_cast(&Camera::setVideoSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setVideoSize)) + .def("setVideoSize", static_cast)>(&Camera::setVideoSize), py::arg("size"), DOC(dai, node, Camera, setVideoSize, 2)) + .def("setStillSize", static_cast(&Camera::setStillSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setStillSize)) + .def("setStillSize", static_cast)>(&Camera::setStillSize), py::arg("size"), DOC(dai, node, Camera, setStillSize, 2)) + // .def("setResolution", &Camera::setResolution, py::arg("resolution"), DOC(dai, node, Camera, setResolution)) + // .def("getResolution", &Camera::getResolution, DOC(dai, node, Camera, getResolution)) + .def("setFps", &Camera::setFps, py::arg("fps"), DOC(dai, node, Camera, setFps)) + .def("getFps", &Camera::getFps, DOC(dai, node, Camera, getFps)) + .def("getPreviewSize", &Camera::getPreviewSize, DOC(dai, node, Camera, getPreviewSize)) + .def("getPreviewWidth", &Camera::getPreviewWidth, DOC(dai, node, Camera, getPreviewWidth)) + .def("getPreviewHeight", &Camera::getPreviewHeight, DOC(dai, node, Camera, getPreviewHeight)) + .def("getVideoSize", &Camera::getVideoSize, DOC(dai, node, Camera, getVideoSize)) + .def("getVideoWidth", &Camera::getVideoWidth, DOC(dai, node, Camera, getVideoWidth)) + .def("getVideoHeight", &Camera::getVideoHeight, DOC(dai, node, Camera, getVideoHeight)) + .def("getStillSize", &Camera::getStillSize, DOC(dai, node, Camera, getStillSize)) + .def("getStillWidth", &Camera::getStillWidth, DOC(dai, node, Camera, getStillWidth)) + .def("getStillHeight", &Camera::getStillHeight, DOC(dai, node, Camera, getStillHeight)) + .def("getResolutionSize", &Camera::getResolutionSize, DOC(dai, node, Camera, getResolutionSize)) + .def("getResolutionWidth", &Camera::getResolutionWidth, DOC(dai, node, Camera, getResolutionWidth)) + .def("getResolutionHeight", &Camera::getResolutionHeight, DOC(dai, node, Camera, getResolutionHeight)) + .def("sensorCenterCrop", &Camera::sensorCenterCrop, DOC(dai, node, Camera, sensorCenterCrop)) + .def("setSensorCrop", &Camera::setSensorCrop, py::arg("x"), py::arg("y"), DOC(dai, node, Camera, setSensorCrop)) + .def("getSensorCrop", &Camera::getSensorCrop, DOC(dai, node, Camera, getSensorCrop)) + .def("getSensorCropX", &Camera::getSensorCropX, DOC(dai, node, Camera, getSensorCropX)) + .def("getSensorCropY", &Camera::getSensorCropY, DOC(dai, node, Camera, getSensorCropY)) + + .def("setWaitForConfigInput", [](Camera& cam, bool wait){ + // Issue a deprecation warning + PyErr_WarnEx(PyExc_DeprecationWarning, "Use 'inputConfig.setWaitForMessage()' instead", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + cam.setWaitForConfigInput(wait); + HEDLEY_DIAGNOSTIC_POP + }, py::arg("wait"), DOC(dai, node, Camera, setWaitForConfigInput)) + + .def("getWaitForConfigInput", [](Camera& cam){ + // Issue a deprecation warning + PyErr_WarnEx(PyExc_DeprecationWarning, "Use 'inputConfig.setWaitForMessage()' instead", 1); + HEDLEY_DIAGNOSTIC_PUSH + HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED + return cam.getWaitForConfigInput(); + HEDLEY_DIAGNOSTIC_POP + }, DOC(dai, node, Camera, getWaitForConfigInput)) + + .def("setPreviewKeepAspectRatio", &Camera::setPreviewKeepAspectRatio, py::arg("keep"), DOC(dai, node, Camera, setPreviewKeepAspectRatio)) + .def("getPreviewKeepAspectRatio", &Camera::getPreviewKeepAspectRatio, DOC(dai, node, Camera, getPreviewKeepAspectRatio)) + .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("numerator"), py::arg("denominator"), DOC(dai, node, Camera, setIspScale)) + .def("setIspScale", static_cast)>(&Camera::setIspScale), py::arg("scale"), DOC(dai, node, Camera, setIspScale, 2)) + .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("horizNum"), py::arg("horizDenom"), py::arg("vertNum"), py::arg("vertDenom"), DOC(dai, node, Camera, setIspScale, 3)) + .def("setIspScale", static_cast,std::tuple)>(&Camera::setIspScale), py::arg("horizScale"), py::arg("vertScale"), DOC(dai, node, Camera, setIspScale, 4)) + .def("getIspSize", &Camera::getIspSize, DOC(dai, node, Camera, getIspSize)) + .def("getIspWidth", &Camera::getIspWidth, DOC(dai, node, Camera, getIspWidth)) + .def("getIspHeight", &Camera::getIspHeight, DOC(dai, node, Camera, getIspHeight)) + + .def("setPreviewNumFramesPool", &Camera::setPreviewNumFramesPool, DOC(dai, node, Camera, setPreviewNumFramesPool)) + .def("setVideoNumFramesPool", &Camera::setVideoNumFramesPool, DOC(dai, node, Camera, setVideoNumFramesPool)) + .def("setStillNumFramesPool", &Camera::setStillNumFramesPool, DOC(dai, node, Camera, setStillNumFramesPool)) + .def("setRawNumFramesPool", &Camera::setRawNumFramesPool, DOC(dai, node, Camera, setRawNumFramesPool)) + .def("setIspNumFramesPool", &Camera::setIspNumFramesPool, DOC(dai, node, Camera, setIspNumFramesPool)) + .def("setNumFramesPool", &Camera::setNumFramesPool, py::arg("raw"), py::arg("isp"), py::arg("preview"), py::arg("video"), py::arg("still"), DOC(dai, node, Camera, setNumFramesPool)) + + .def("getPreviewNumFramesPool", &Camera::getPreviewNumFramesPool, DOC(dai, node, Camera, getPreviewNumFramesPool)) + .def("getVideoNumFramesPool", &Camera::getVideoNumFramesPool, DOC(dai, node, Camera, getVideoNumFramesPool)) + .def("getStillNumFramesPool", &Camera::getStillNumFramesPool, DOC(dai, node, Camera, getStillNumFramesPool)) + .def("getRawNumFramesPool", &Camera::getRawNumFramesPool, DOC(dai, node, Camera, getRawNumFramesPool)) + .def("getIspNumFramesPool", &Camera::getIspNumFramesPool, DOC(dai, node, Camera, getIspNumFramesPool)) + .def("setCamera", &Camera::setCamera, py::arg("name"), DOC(dai, node, Camera, setCamera)) + .def("getCamera", &Camera::getCamera, DOC(dai, node, Camera, getCamera)) + ; + // ALIAS + daiNodeModule.attr("Camera").attr("Properties") = cameraProperties; + +} diff --git a/src/pipeline/node/NodeBindings.cpp b/src/pipeline/node/NodeBindings.cpp index 21a591367..222ca997c 100644 --- a/src/pipeline/node/NodeBindings.cpp +++ b/src/pipeline/node/NodeBindings.cpp @@ -94,6 +94,7 @@ py::class_ bindNodeMap(py::handle scope, const std::string &na void bind_xlinkin(pybind11::module& m, void* pCallstack); void bind_xlinkout(pybind11::module& m, void* pCallstack); void bind_colorcamera(pybind11::module& m, void* pCallstack); +void bind_camera(pybind11::module& m, void* pCallstack); void bind_monocamera(pybind11::module& m, void* pCallstack); void bind_stereodepth(pybind11::module& m, void* pCallstack); void bind_neuralnetwork(pybind11::module& m, void* pCallstack); @@ -122,6 +123,7 @@ void NodeBindings::addToCallstack(std::deque& callstack) { callstack.push_front(bind_xlinkin); callstack.push_front(bind_xlinkout); callstack.push_front(bind_colorcamera); + callstack.push_front(bind_camera); callstack.push_front(bind_monocamera); callstack.push_front(bind_stereodepth); callstack.push_front(bind_neuralnetwork); From 13bd22c1331fd83f0b3ac389b1d461a4b9ec087e Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 14 Dec 2022 16:45:32 +0200 Subject: [PATCH 10/43] Update FW: Add missing python bindings for boundingBoxMapping --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index c95a06aac..3bac6a8d8 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit c95a06aac4b51bc062bed390ec83f5377fdea337 +Subproject commit 3bac6a8d80ee6d8aba69bd81058de12181e40007 From 3d5b514e4a3c199a93aced0293ec722a948a3bfc Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 16 Dec 2022 14:47:10 +0100 Subject: [PATCH 11/43] Updated NETWORK Bootloader with dual protocol capabilities --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 3bac6a8d8..0afad8f5c 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 3bac6a8d80ee6d8aba69bd81058de12181e40007 +Subproject commit 0afad8f5cf472f1609c91b0c7c26f27227f4fb93 From 3bd8b582541d04bc6e594a42648b8d47eab04257 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 16 Dec 2022 22:43:54 +0100 Subject: [PATCH 12/43] Added some bindings and modified camera preview example --- examples/Camera/camera_preview.py | 43 +++++++++++++++++++++++++ examples/Camera/camera_rgb_preview.py | 46 --------------------------- src/pipeline/node/CameraBindings.cpp | 4 +++ 3 files changed, 47 insertions(+), 46 deletions(-) create mode 100755 examples/Camera/camera_preview.py delete mode 100755 examples/Camera/camera_rgb_preview.py diff --git a/examples/Camera/camera_preview.py b/examples/Camera/camera_preview.py new file mode 100755 index 000000000..2e59f4535 --- /dev/null +++ b/examples/Camera/camera_preview.py @@ -0,0 +1,43 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai + +# Connect to device and start pipeline +with dai.Device() as device: + print('Connected cameras:', device.getConnectedCameraFeatures()) + # Print out usb speed + print('Usb speed:', device.getUsbSpeed().name) + + # Create pipeline + pipeline = dai.Pipeline() + cams = device.getConnectedCameraFeatures() + streams = [] + for cam in cams: + c = pipeline.create(dai.node.Camera) + x = pipeline.create(dai.node.XLinkOut) + c.preview.link(x.input) + stream = str(cam.socket) + x.setStreamName(stream) + streams.append(stream) + + # Bootloader version + if device.getBootloaderVersion() is not None: + print('Bootloader version:', device.getBootloaderVersion()) + # Device name + print('Device name:', device.getDeviceName()) + + # Start pipeline + device.startPipeline(pipeline) + # Clear queue events + device.getQueueEvents() + while True: + + queueName = device.getQueueEvent(streams) + message = device.getOutputQueue(queueName).get() + # Display arrived frames + if type(message) == dai.ImgFrame: + cv2.imshow(queueName, message.getCvFrame()) + + if cv2.waitKey(1) == ord('q'): + break diff --git a/examples/Camera/camera_rgb_preview.py b/examples/Camera/camera_rgb_preview.py deleted file mode 100755 index 8960651d0..000000000 --- a/examples/Camera/camera_rgb_preview.py +++ /dev/null @@ -1,46 +0,0 @@ -#!/usr/bin/env python3 - -import cv2 -import depthai as dai - -# Create pipeline -pipeline = dai.Pipeline() - -# Define source and output -cam = pipeline.create(dai.node.Camera) -xoutRgb = pipeline.create(dai.node.XLinkOut) - -xoutRgb.setStreamName("camera") - -# Properties -cam.setPreviewSize(300, 300) -cam.setInterleaved(False) -cam.setColorOrder(dai.CameraProperties.ColorOrder.RGB) -cam.setBoardSocket(dai.CameraBoardSocket.LEFT) - -# Linking -cam.isp.link(xoutRgb.input) - -# Connect to device and start pipeline -with dai.Device(pipeline) as device: - - print('Connected cameras:', device.getConnectedCameraFeatures()) - # Print out usb speed - print('Usb speed:', device.getUsbSpeed().name) - # Bootloader version - if device.getBootloaderVersion() is not None: - print('Bootloader version:', device.getBootloaderVersion()) - # Device name - print('Device name:', device.getDeviceName()) - - # Output queue will be used to get the rgb frames from the output defined above - qRgb = device.getOutputQueue(name="camera", maxSize=4, blocking=False) - - while True: - inRgb = qRgb.get() # blocking call, will wait until a new data has arrived - - # Retrieve 'bgr' (opencv format) frame - cv2.imshow("camera", inRgb.getCvFrame()) - - if cv2.waitKey(1) == ord('q'): - break diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp index 98624b0eb..042e5a91f 100644 --- a/src/pipeline/node/CameraBindings.cpp +++ b/src/pipeline/node/CameraBindings.cpp @@ -182,6 +182,10 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def("getIspNumFramesPool", &Camera::getIspNumFramesPool, DOC(dai, node, Camera, getIspNumFramesPool)) .def("setCamera", &Camera::setCamera, py::arg("name"), DOC(dai, node, Camera, setCamera)) .def("getCamera", &Camera::getCamera, DOC(dai, node, Camera, getCamera)) + + .def("setSensorSize", static_cast(&Camera::setSensorSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setSensorSize)) + .def("setSensorSize", static_cast)>(&Camera::setSensorSize), py::arg("size"), DOC(dai, node, Camera, setSensorSize, 2)) + ; // ALIAS daiNodeModule.attr("Camera").attr("Properties") = cameraProperties; From 997fd8f86012243ee9be02c457989fcdfd1f4752 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Sat, 17 Dec 2022 02:47:16 +0100 Subject: [PATCH 13/43] [FW] Fixed a bug in board downselection. OAK-D S2/Pro camera enumeration fix. --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 3bac6a8d8..744674523 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 3bac6a8d80ee6d8aba69bd81058de12181e40007 +Subproject commit 74467452363fa90fe9354135e2e6ced0bba7e5b8 From bae849d70627b3df62d8822b644acc36b86652d8 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Sat, 17 Dec 2022 04:15:16 +0100 Subject: [PATCH 14/43] Updated camera_preview example --- examples/Camera/camera_preview.py | 37 +++++++++++-------------------- 1 file changed, 13 insertions(+), 24 deletions(-) diff --git a/examples/Camera/camera_preview.py b/examples/Camera/camera_preview.py index 2e59f4535..397ebf516 100755 --- a/examples/Camera/camera_preview.py +++ b/examples/Camera/camera_preview.py @@ -1,43 +1,32 @@ #!/usr/bin/env python3 - import cv2 import depthai as dai -# Connect to device and start pipeline +# Connect to device with dai.Device() as device: - print('Connected cameras:', device.getConnectedCameraFeatures()) - # Print out usb speed - print('Usb speed:', device.getUsbSpeed().name) - # Create pipeline pipeline = dai.Pipeline() cams = device.getConnectedCameraFeatures() streams = [] for cam in cams: + print(str(cam), str(cam.socket), cam.socket) c = pipeline.create(dai.node.Camera) x = pipeline.create(dai.node.XLinkOut) - c.preview.link(x.input) + c.isp.link(x.input) + c.setBoardSocket(cam.socket) stream = str(cam.socket) + if cam.name: + stream = f'{cam.name} ({stream})' x.setStreamName(stream) streams.append(stream) - - # Bootloader version - if device.getBootloaderVersion() is not None: - print('Bootloader version:', device.getBootloaderVersion()) - # Device name - print('Device name:', device.getDeviceName()) - # Start pipeline device.startPipeline(pipeline) - # Clear queue events - device.getQueueEvents() - while True: - - queueName = device.getQueueEvent(streams) - message = device.getOutputQueue(queueName).get() - # Display arrived frames - if type(message) == dai.ImgFrame: - cv2.imshow(queueName, message.getCvFrame()) - + while not device.isClosed(): + queueNames = device.getQueueEvents(streams) + for q in queueNames: + message = device.getOutputQueue(q).get() + # Display arrived frames + if type(message) == dai.ImgFrame: + cv2.imshow(q, message.getCvFrame()) if cv2.waitKey(1) == ord('q'): break From 3b3766f7539de37365b2c1f67b919f02378cc90f Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Sat, 17 Dec 2022 12:35:12 +0100 Subject: [PATCH 15/43] [FW] Added support for Mono video/preview in Camera node --- depthai-core | 2 +- examples/Camera/camera_preview.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index 26ba3000c..de4db9aa5 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 26ba3000c853d085e1ac35a9d9cf898ce546b6d0 +Subproject commit de4db9aa54fb5f17fc37eef2930efc8105661990 diff --git a/examples/Camera/camera_preview.py b/examples/Camera/camera_preview.py index 397ebf516..7e91f6017 100755 --- a/examples/Camera/camera_preview.py +++ b/examples/Camera/camera_preview.py @@ -12,7 +12,7 @@ print(str(cam), str(cam.socket), cam.socket) c = pipeline.create(dai.node.Camera) x = pipeline.create(dai.node.XLinkOut) - c.isp.link(x.input) + c.preview.link(x.input) c.setBoardSocket(cam.socket) stream = str(cam.socket) if cam.name: From 8f23f967df25dce484bf205fe058e6f4b941c494 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sun, 18 Dec 2022 21:52:38 +0100 Subject: [PATCH 16/43] Added workflow notify for HIL tests --- .github/workflows/main.yml | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index e4145a19d..e6a02d277 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -538,3 +538,15 @@ jobs: repository: luxonis/robothub-apps event-type: depthai-python-release client-payload: '{"ref": "${{ github.ref }}", "sha": "${{ github.sha }}"}' + + notify_hil_workflow_linux_x86_64: + needs: [build-linux-x86_64] + runs-on: ubuntu-latest + steps: + - name: Repository Dispatch + uses: peter-evans/repository-dispatch@v2 + with: + token: ${{ secrets.HIL_CORE_DISPATCH_TOKEN }} + repository: luxonis/depthai-core-hil-tests + event-type: python-hil-event + client-payload: '{"ref": "${{ github.ref }}", "sha": "${{ github.sha }}"}' \ No newline at end of file From e5e841c9730a1e0477ab2364c9035686b64866a0 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 19 Dec 2022 14:49:52 +0100 Subject: [PATCH 17/43] Updated dual BL to v0.0.23 temporary build --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 0afad8f5c..56cb5b2f5 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 0afad8f5cf472f1609c91b0c7c26f27227f4fb93 +Subproject commit 56cb5b2f5498facbfcb4afd74c2897ed0f221361 From f26cb3b61a345ff9e522132ca6afee54ab72633b Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 19 Dec 2022 19:23:45 +0100 Subject: [PATCH 18/43] Added OAK-D-LR support. WIP: Orientation capability --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 5ebfc2ee9..401e41162 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 5ebfc2ee9a9c51d34085aa34aa8a2e0c92b8e073 +Subproject commit 401e4116246d5e46451c379c4b5fb5c7a5457773 From a9ece1ff08aac4830a625869b89f8fea7a07cafa Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 19 Dec 2022 22:13:24 +0100 Subject: [PATCH 19/43] [FW/XLink] Explicitly limited to single connection --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 6e945e428..e30a8b9b8 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 6e945e428aae604f9714ee2a1c7c7ec353ad65b4 +Subproject commit e30a8b9b8bf4e278a3ff0f0c7e0ac528641177f9 From 531a38495039538726713175d39c780bda88a03b Mon Sep 17 00:00:00 2001 From: Tommy Date: Mon, 19 Dec 2022 22:51:41 +0100 Subject: [PATCH 20/43] Add python bindings for frame event --- depthai-core | 2 +- src/pipeline/node/ColorCameraBindings.cpp | 3 +++ src/pipeline/node/MonoCameraBindings.cpp | 3 +++ 3 files changed, 7 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 744674523..4e324ba00 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 74467452363fa90fe9354135e2e6ced0bba7e5b8 +Subproject commit 4e324ba0036017a2d04963695fc9e587993c0dd3 diff --git a/src/pipeline/node/ColorCameraBindings.cpp b/src/pipeline/node/ColorCameraBindings.cpp index 48956281f..cd39b8cc3 100644 --- a/src/pipeline/node/ColorCameraBindings.cpp +++ b/src/pipeline/node/ColorCameraBindings.cpp @@ -73,6 +73,7 @@ void bind_colorcamera(pybind11::module& m, void* pCallstack){ .def_readwrite("numFramesPoolVideo", &ColorCameraProperties::numFramesPoolVideo) .def_readwrite("numFramesPoolPreview", &ColorCameraProperties::numFramesPoolPreview) .def_readwrite("numFramesPoolStill", &ColorCameraProperties::numFramesPoolStill) + .def_readwrite("eventFilter", &ColorCameraProperties::eventFilter) ; // ColorCamera node @@ -122,6 +123,8 @@ void bind_colorcamera(pybind11::module& m, void* pCallstack){ .def("getResolution", &ColorCamera::getResolution, DOC(dai, node, ColorCamera, getResolution)) .def("setFps", &ColorCamera::setFps, py::arg("fps"), DOC(dai, node, ColorCamera, setFps)) .def("getFps", &ColorCamera::getFps, DOC(dai, node, ColorCamera, getFps)) + .def("setFrameEventFilter", &ColorCamera::setFrameEventFilter, py::arg("events"), DOC(dai, node, ColorCamera, setFrameEventFilter)) + .def("getFrameEventFilter", &ColorCamera::getFrameEventFilter, DOC(dai, node, ColorCamera, getFrameEventFilter)) .def("getPreviewSize", &ColorCamera::getPreviewSize, DOC(dai, node, ColorCamera, getPreviewSize)) .def("getPreviewWidth", &ColorCamera::getPreviewWidth, DOC(dai, node, ColorCamera, getPreviewWidth)) .def("getPreviewHeight", &ColorCamera::getPreviewHeight, DOC(dai, node, ColorCamera, getPreviewHeight)) diff --git a/src/pipeline/node/MonoCameraBindings.cpp b/src/pipeline/node/MonoCameraBindings.cpp index b25acaf6d..5ff0bf685 100644 --- a/src/pipeline/node/MonoCameraBindings.cpp +++ b/src/pipeline/node/MonoCameraBindings.cpp @@ -45,6 +45,7 @@ void bind_monocamera(pybind11::module& m, void* pCallstack){ .def_readwrite("fps", &MonoCameraProperties::fps) .def_readwrite("numFramesPool", &MonoCameraProperties::numFramesPool) .def_readwrite("numFramesPoolRaw", &MonoCameraProperties::numFramesPoolRaw) + .def_readwrite("eventFilter", &MonoCameraProperties::eventFilter) ; // Node @@ -76,6 +77,8 @@ void bind_monocamera(pybind11::module& m, void* pCallstack){ .def("getImageOrientation", &MonoCamera::getImageOrientation, DOC(dai, node, MonoCamera, getImageOrientation)) .def("setResolution", &MonoCamera::setResolution, py::arg("resolution"), DOC(dai, node, MonoCamera, setResolution)) .def("getResolution", &MonoCamera::getResolution, DOC(dai, node, MonoCamera, getResolution)) + .def("setFrameEventFilter", &MonoCamera::setFrameEventFilter, py::arg("events"), DOC(dai, node, MonoCamera, setFrameEventFilter)) + .def("getFrameEventFilter", &MonoCamera::getFrameEventFilter, DOC(dai, node, MonoCamera, getFrameEventFilter)) .def("setFps", &MonoCamera::setFps, py::arg("fps"), DOC(dai, node, MonoCamera, setFps)) .def("getFps", &MonoCamera::getFps, DOC(dai, node, MonoCamera, getFps)) .def("getResolutionSize", &MonoCamera::getResolutionSize, DOC(dai, node, MonoCamera, getResolutionSize)) From 646d52e91329348b3ca96ea976b97857706edf93 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Wed, 21 Dec 2022 17:13:37 +0100 Subject: [PATCH 21/43] ImageManip added colormap capability. TODO min/max range selection --- depthai-core | 2 +- examples/StereoDepth/depth_colormap.py | 62 +++++++++++++++++++ src/pipeline/CommonBindings.cpp | 28 +++++++++ .../datatype/ImageManipConfigBindings.cpp | 4 +- 4 files changed, 94 insertions(+), 2 deletions(-) create mode 100755 examples/StereoDepth/depth_colormap.py diff --git a/depthai-core b/depthai-core index de4db9aa5..89665e38d 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit de4db9aa54fb5f17fc37eef2930efc8105661990 +Subproject commit 89665e38d1192c90d25d03950828670bcc289d6d diff --git a/examples/StereoDepth/depth_colormap.py b/examples/StereoDepth/depth_colormap.py new file mode 100755 index 000000000..b334ffb34 --- /dev/null +++ b/examples/StereoDepth/depth_colormap.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai +import numpy as np + +# Closer-in minimum depth, disparity range is doubled (from 95 to 190): +extended_disparity = False +# Better accuracy for longer distance, fractional disparity 32-levels: +subpixel = False +# Better handling for occlusions: +lr_check = True + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +monoLeft = pipeline.create(dai.node.MonoCamera) +monoRight = pipeline.create(dai.node.MonoCamera) +depth = pipeline.create(dai.node.StereoDepth) +xout = pipeline.create(dai.node.XLinkOut) + +xout.setStreamName("disparity") + +# 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) + +# Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way) +depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY) +# Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default) +depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7) +depth.setLeftRightCheck(lr_check) +depth.setExtendedDisparity(extended_disparity) +depth.setSubpixel(subpixel) + +# Create a colormap +colormap = pipeline.create(dai.node.ImageManip) +colormap.initialConfig.setColormap(dai.Colormap.TURBO, 0, 95) +colormap.initialConfig.setFrameType(dai.ImgFrame.Type.NV12) + +# Linking +monoLeft.out.link(depth.left) +monoRight.out.link(depth.right) +depth.disparity.link(colormap.inputImage) +colormap.out.link(xout.input) + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + # Output queue will be used to get the disparity frames from the outputs defined above + q = device.getOutputQueue(name="disparity", maxSize=4, blocking=False) + + while True: + inDisparity = q.get() # blocking call, will wait until a new data has arrived + frame = inDisparity.getCvFrame() + cv2.imshow("disparity", frame) + + if cv2.waitKey(1) == ord('q'): + break \ No newline at end of file diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 2f8c346bc..9c1602f74 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -19,6 +19,7 @@ #include "depthai-shared/common/DetectionParserOptions.hpp" #include "depthai-shared/common/RotatedRect.hpp" #include "depthai-shared/common/Rect.hpp" +#include "depthai-shared/common/Colormap.hpp" // depthai #include "depthai/common/CameraFeatures.hpp" @@ -50,6 +51,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ py::class_ detectionParserOptions(m, "DetectionParserOptions", DOC(dai, DetectionParserOptions)); py::class_ rotatedRect(m, "RotatedRect", DOC(dai, RotatedRect)); py::class_ rect(m, "Rect", DOC(dai, Rect)); + py::enum_ colormap(m, "Colormap", DOC(dai, Colormap)); /////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////// @@ -290,4 +292,30 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ .def_readwrite("iouThreshold", &DetectionParserOptions::iouThreshold) ; + colormap + .value("NONE", Colormap::NONE) + .value("AUTUMN", Colormap::AUTUMN) + .value("BONE", Colormap::BONE) + .value("JET", Colormap::JET) + .value("WINTER", Colormap::WINTER) + .value("RAINBOW", Colormap::RAINBOW) + .value("OCEAN", Colormap::OCEAN) + .value("SUMMER", Colormap::SUMMER) + .value("SPRING", Colormap::SPRING) + .value("COOL", Colormap::COOL) + .value("HSV", Colormap::HSV) + .value("PINK", Colormap::PINK) + .value("HOT", Colormap::HOT) + .value("PARULA", Colormap::PARULA) + .value("MAGMA", Colormap::MAGMA) + .value("INFERNO", Colormap::INFERNO) + .value("PLASMA", Colormap::PLASMA) + .value("VIRIDIS", Colormap::VIRIDIS) + .value("CIVIDIS", Colormap::CIVIDIS) + .value("TWILIGHT", Colormap::TWILIGHT) + .value("TWILIGHT_SHIFTED", Colormap::TWILIGHT_SHIFTED) + .value("TURBO", Colormap::TURBO) + .value("DEEPGREEN", Colormap::DEEPGREEN) + ; + } diff --git a/src/pipeline/datatype/ImageManipConfigBindings.cpp b/src/pipeline/datatype/ImageManipConfigBindings.cpp index 1ead6d0cc..05b3f38c2 100644 --- a/src/pipeline/datatype/ImageManipConfigBindings.cpp +++ b/src/pipeline/datatype/ImageManipConfigBindings.cpp @@ -111,7 +111,8 @@ void bind_imagemanipconfig(pybind11::module& m, void* pCallstack){ .def("setResize", static_cast)>(&ImageManipConfig::setResize), py::arg("size"), DOC(dai, ImageManipConfig, setResize, 2)) .def("setResizeThumbnail", static_cast(&ImageManipConfig::setResizeThumbnail), py::arg("w"), py::arg("h"), py::arg("bgRed")=0, py::arg("bgGreen")=0, py::arg("bgBlue")=0, DOC(dai, ImageManipConfig, setResizeThumbnail)) .def("setResizeThumbnail", static_cast, int, int, int)>(&ImageManipConfig::setResizeThumbnail), py::arg("size"), py::arg("bgRed")=0, py::arg("bgGreen")=0, py::arg("bgBlue")=0, DOC(dai, ImageManipConfig, setResizeThumbnail, 2)) - .def("setFrameType", &ImageManipConfig::setFrameType, py::arg("name"), DOC(dai, ImageManipConfig, setFrameType)) + .def("setFrameType", &ImageManipConfig::setFrameType, py::arg("type"), DOC(dai, ImageManipConfig, setFrameType)) + .def("setColormap", &ImageManipConfig::setColormap, py::arg("colormap"), py::arg("min") = 0, py::arg("max") = 255, DOC(dai, ImageManipConfig, setColormap)) .def("setHorizontalFlip", &ImageManipConfig::setHorizontalFlip, py::arg("flip"), DOC(dai, ImageManipConfig, setHorizontalFlip)) .def("setVerticalFlip", &ImageManipConfig::setVerticalFlip, py::arg("flip"), DOC(dai, ImageManipConfig, setVerticalFlip)) .def("setReusePreviousImage", &ImageManipConfig::setReusePreviousImage, py::arg("reuse"), DOC(dai, ImageManipConfig, setReusePreviousImage)) @@ -129,6 +130,7 @@ void bind_imagemanipconfig(pybind11::module& m, void* pCallstack){ .def("getResizeConfig", &ImageManipConfig::getResizeConfig, DOC(dai, ImageManipConfig, getResizeConfig)) .def("getFormatConfig", &ImageManipConfig::getFormatConfig, DOC(dai, ImageManipConfig, getFormatConfig)) .def("isResizeThumbnail", &ImageManipConfig::isResizeThumbnail, DOC(dai, ImageManipConfig, isResizeThumbnail)) + .def("getColormap", &ImageManipConfig::getColormap, DOC(dai, ImageManipConfig, getColormap)) ; From 6cfdd5675852dac373922a303526d7195bbb4178 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Thu, 22 Dec 2022 20:24:57 +0200 Subject: [PATCH 22/43] Add option to override baseline and/or focal length for disparity to depth conversion --- depthai-core | 2 +- src/pipeline/node/StereoDepthBindings.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index bc8dce62a..9e199d526 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit bc8dce62acbf47194fe904e10cf4fe40ecb2db74 +Subproject commit 9e199d526914d7b7cdad39c29684feb73b749d45 diff --git a/src/pipeline/node/StereoDepthBindings.cpp b/src/pipeline/node/StereoDepthBindings.cpp index de473accd..1ed9e43cb 100644 --- a/src/pipeline/node/StereoDepthBindings.cpp +++ b/src/pipeline/node/StereoDepthBindings.cpp @@ -166,6 +166,8 @@ void bind_stereodepth(pybind11::module& m, void* pCallstack){ }, DOC(dai, node, StereoDepth, setFocalLengthFromCalibration)) .def("useHomographyRectification", &StereoDepth::useHomographyRectification, DOC(dai, node, StereoDepth, useHomographyRectification)) .def("enableDistortionCorrection", &StereoDepth::enableDistortionCorrection, DOC(dai, node, StereoDepth, enableDistortionCorrection)) + .def("setBaseline", &StereoDepth::setBaseline, DOC(dai, node, StereoDepth, setBaseline)) + .def("setFocalLength", &StereoDepth::setFocalLength, DOC(dai, node, StereoDepth, setFocalLength)) ; // ALIAS daiNodeModule.attr("StereoDepth").attr("Properties") = stereoDepthProperties; From fb04df87c5068b26b501ead531dba90e30751e74 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 23 Dec 2022 02:47:29 +0100 Subject: [PATCH 23/43] [FW] OAK-D-LR - Fixed default image orientation and added depth preview example --- depthai-core | 2 +- examples/StereoDepth/depth_preview_lr.py | 64 ++++++++++++++++++++++++ 2 files changed, 65 insertions(+), 1 deletion(-) create mode 100755 examples/StereoDepth/depth_preview_lr.py diff --git a/depthai-core b/depthai-core index bc8dce62a..1eb01248f 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit bc8dce62acbf47194fe904e10cf4fe40ecb2db74 +Subproject commit 1eb01248fb7e994b51ceec91984bff46e0a5d5f2 diff --git a/examples/StereoDepth/depth_preview_lr.py b/examples/StereoDepth/depth_preview_lr.py new file mode 100755 index 000000000..82caea026 --- /dev/null +++ b/examples/StereoDepth/depth_preview_lr.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai +import numpy as np + +# Closer-in minimum depth, disparity range is doubled (from 95 to 190): +extended_disparity = False +# Better accuracy for longer distance, fractional disparity 32-levels: +subpixel = False +# Better handling for occlusions: +lr_check = True + +# Create pipeline +pipeline = dai.Pipeline() + +# Define sources and outputs +left = pipeline.create(dai.node.ColorCamera) +right = pipeline.create(dai.node.ColorCamera) +depth = pipeline.create(dai.node.StereoDepth) +xout = pipeline.create(dai.node.XLinkOut) +xoutl = pipeline.create(dai.node.XLinkOut) +xoutr = pipeline.create(dai.node.XLinkOut) + +xout.setStreamName("disparity") +xoutl.setStreamName("rectifiedLeft") +xoutr.setStreamName("rectifiedRight") + +# Properties +left.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1200_P) +left.setBoardSocket(dai.CameraBoardSocket.LEFT) +right.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1200_P) +right.setBoardSocket(dai.CameraBoardSocket.RIGHT) +right.setIspScale(2, 3) +left.setIspScale(2, 3) + + +# Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way) +depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY) +# Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default) +depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7) +depth.setInputResolution(1280, 800) +depth.setLeftRightCheck(lr_check) +depth.setExtendedDisparity(extended_disparity) +depth.setSubpixel(subpixel) + +# Linking +left.isp.link(depth.left) +right.isp.link(depth.right) +depth.disparity.link(xout.input) +depth.rectifiedLeft.link(xoutl.input) +depth.rectifiedRight.link(xoutr.input) + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + while not device.isClosed(): + queueNames = device.getQueueEvents() + for q in queueNames: + message = device.getOutputQueue(q).get() + # Display arrived frames + if type(message) == dai.ImgFrame: + cv2.imshow(q, message.getCvFrame()) + if cv2.waitKey(1) == ord('q'): + break \ No newline at end of file From 0804b7ccac8fd32b4fe9173d31f06a72e2189c60 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 27 Dec 2022 12:39:44 +0100 Subject: [PATCH 24/43] Modified LR depth example --- examples/StereoDepth/depth_preview_lr.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/examples/StereoDepth/depth_preview_lr.py b/examples/StereoDepth/depth_preview_lr.py index 82caea026..7d62b0302 100755 --- a/examples/StereoDepth/depth_preview_lr.py +++ b/examples/StereoDepth/depth_preview_lr.py @@ -5,9 +5,9 @@ import numpy as np # Closer-in minimum depth, disparity range is doubled (from 95 to 190): -extended_disparity = False +extended_disparity = True # Better accuracy for longer distance, fractional disparity 32-levels: -subpixel = False +subpixel = True # Better handling for occlusions: lr_check = True @@ -43,6 +43,7 @@ depth.setLeftRightCheck(lr_check) depth.setExtendedDisparity(extended_disparity) depth.setSubpixel(subpixel) +depth.setInputResolution(1280, 800) # Linking left.isp.link(depth.left) @@ -59,6 +60,13 @@ message = device.getOutputQueue(q).get() # Display arrived frames if type(message) == dai.ImgFrame: - cv2.imshow(q, message.getCvFrame()) + frame = message.getCvFrame() + if 'disparity' in q: + maxDisp = depth.initialConfig.getMaxDisparity() + disp = (frame * (255.0 / maxDisp)).astype(np.uint8) + disp = cv2.applyColorMap(disp, cv2.COLORMAP_JET) + cv2.imshow(q, disp) + else: + cv2.imshow(q, frame) if cv2.waitKey(1) == ord('q'): break \ No newline at end of file From c7e4a29f5e79ae6cbe3ac19462c71db959d4def4 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Wed, 28 Dec 2022 20:02:58 +0100 Subject: [PATCH 25/43] Fixed image_manip_warp_mesh.py example --- examples/ImageManip/image_manip_warp_mesh.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/ImageManip/image_manip_warp_mesh.py b/examples/ImageManip/image_manip_warp_mesh.py index 3eeaa43da..eadff4c77 100644 --- a/examples/ImageManip/image_manip_warp_mesh.py +++ b/examples/ImageManip/image_manip_warp_mesh.py @@ -12,7 +12,7 @@ maxFrameSize = camRgb.getPreviewWidth() * camRgb.getPreviewHeight() * 3 # Warp preview frame 1 -manip1 = pipeline.create(dai.node.Warp) +manip1 = pipeline.create(dai.node.ImageManip) # Create a custom warp mesh tl = dai.Point2f(20, 20) tr = dai.Point2f(460, 20) From 1c868cff81fad929357ac9ed3f69b792afb3e417 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 29 Dec 2022 16:16:03 +0100 Subject: [PATCH 26/43] Updated FW with Camera changes and warp capabilities. Modified camera_preview example --- depthai-core | 2 +- examples/Camera/camera_preview.py | 44 +++++++++++++++--- src/pipeline/node/CameraBindings.cpp | 67 +++------------------------- 3 files changed, 43 insertions(+), 70 deletions(-) diff --git a/depthai-core b/depthai-core index 89665e38d..baa24cead 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 89665e38d1192c90d25d03950828670bcc289d6d +Subproject commit baa24cead9524c10f7dada7cc28db60a5751737f diff --git a/examples/Camera/camera_preview.py b/examples/Camera/camera_preview.py index 7e91f6017..5516b19a8 100755 --- a/examples/Camera/camera_preview.py +++ b/examples/Camera/camera_preview.py @@ -1,9 +1,21 @@ #!/usr/bin/env python3 + import cv2 import depthai as dai +import time + +# Connect to device and start pipeline +with dai.Device(dai.OpenVINO.VERSION_2021_1, dai.UsbSpeed.SUPER_PLUS) as device: + # Device name + print('Device name:', device.getDeviceName()) + # Bootloader version + if device.getBootloaderVersion() is not None: + print('Bootloader version:', device.getBootloaderVersion()) + # Print out usb speed + print('Usb speed:', device.getUsbSpeed().name) + # Connected cameras + print('Connected cameras:', device.getConnectedCameraFeatures()) -# Connect to device -with dai.Device() as device: # Create pipeline pipeline = dai.Pipeline() cams = device.getConnectedCameraFeatures() @@ -19,14 +31,32 @@ stream = f'{cam.name} ({stream})' x.setStreamName(stream) streams.append(stream) + # Start pipeline device.startPipeline(pipeline) + fpsCounter = {} + lastFpsCount = {} + tfps = time.time() while not device.isClosed(): queueNames = device.getQueueEvents(streams) - for q in queueNames: - message = device.getOutputQueue(q).get() - # Display arrived frames - if type(message) == dai.ImgFrame: - cv2.imshow(q, message.getCvFrame()) + for stream in queueNames: + messages = device.getOutputQueue(stream).tryGetAll() + fpsCounter[stream] = fpsCounter.get(stream, 0.0) + len(messages) + for message in messages: + # Display arrived frames + if type(message) == dai.ImgFrame: + # render fps + fps = lastFpsCount.get(stream, 0) + frame = message.getCvFrame() + cv2.putText(frame, "Fps: {:.2f}".format(fps), (10, 10), cv2.FONT_HERSHEY_TRIPLEX, 0.4, (255,255,255)) + cv2.imshow(stream, frame) + + if time.time() - tfps >= 1.0: + scale = time.time() - tfps + for stream in fpsCounter.keys(): + lastFpsCount[stream] = fpsCounter[stream] / scale + fpsCounter = {} + tfps = time.time() + if cv2.waitKey(1) == ord('q'): break diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp index 042e5a91f..0e5c935be 100644 --- a/src/pipeline/node/CameraBindings.cpp +++ b/src/pipeline/node/CameraBindings.cpp @@ -86,32 +86,10 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def_readonly("isp", &Camera::isp, DOC(dai, node, Camera, isp)) .def_readonly("raw", &Camera::raw, DOC(dai, node, Camera, raw)) .def_readonly("frameEvent", &Camera::frameEvent, DOC(dai, node, Camera, frameEvent)) - .def("setCamId", [](Camera& c, int64_t id) { - // Issue an deprecation warning - PyErr_WarnEx(PyExc_DeprecationWarning, "setCamId() is deprecated, use setBoardSocket() instead.", 1); - HEDLEY_DIAGNOSTIC_PUSH - HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED - c.setCamId(id); - HEDLEY_DIAGNOSTIC_POP - }) - .def("getCamId", [](Camera& c) { - // Issue an deprecation warning - PyErr_WarnEx(PyExc_DeprecationWarning, "getCamId() is deprecated, use getBoardSocket() instead.", 1); - HEDLEY_DIAGNOSTIC_PUSH - HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED - return c.getCamId(); - HEDLEY_DIAGNOSTIC_POP - }) .def("setBoardSocket", &Camera::setBoardSocket, py::arg("boardSocket"), DOC(dai, node, Camera, setBoardSocket)) .def("getBoardSocket", &Camera::getBoardSocket, DOC(dai, node, Camera, getBoardSocket)) .def("setImageOrientation", &Camera::setImageOrientation, py::arg("imageOrientation"), DOC(dai, node, Camera, setImageOrientation)) .def("getImageOrientation", &Camera::getImageOrientation, DOC(dai, node, Camera, getImageOrientation)) - .def("setColorOrder", &Camera::setColorOrder, py::arg("colorOrder"), DOC(dai, node, Camera, setColorOrder)) - .def("getColorOrder", &Camera::getColorOrder, DOC(dai, node, Camera, getColorOrder)) - .def("setInterleaved", &Camera::setInterleaved, py::arg("interleaved"), DOC(dai, node, Camera, setInterleaved)) - .def("getInterleaved", &Camera::getInterleaved, DOC(dai, node, Camera, getInterleaved)) - .def("setFp16", &Camera::setFp16, py::arg("fp16"), DOC(dai, node, Camera, setFp16)) - .def("getFp16", &Camera::getFp16, DOC(dai, node, Camera, getFp16)) .def("setPreviewSize", static_cast(&Camera::setPreviewSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setPreviewSize)) .def("setPreviewSize", static_cast)>(&Camera::setPreviewSize), py::arg("size"), DOC(dai, node, Camera, setPreviewSize, 2)) .def("setVideoSize", static_cast(&Camera::setVideoSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setVideoSize)) @@ -131,60 +109,25 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def("getStillSize", &Camera::getStillSize, DOC(dai, node, Camera, getStillSize)) .def("getStillWidth", &Camera::getStillWidth, DOC(dai, node, Camera, getStillWidth)) .def("getStillHeight", &Camera::getStillHeight, DOC(dai, node, Camera, getStillHeight)) - .def("getResolutionSize", &Camera::getResolutionSize, DOC(dai, node, Camera, getResolutionSize)) - .def("getResolutionWidth", &Camera::getResolutionWidth, DOC(dai, node, Camera, getResolutionWidth)) - .def("getResolutionHeight", &Camera::getResolutionHeight, DOC(dai, node, Camera, getResolutionHeight)) + .def("getSize", &Camera::getSize, DOC(dai, node, Camera, getSize)) + .def("getWidth", &Camera::getWidth, DOC(dai, node, Camera, getWidth)) + .def("getHeight", &Camera::getHeight, DOC(dai, node, Camera, getHeight)) .def("sensorCenterCrop", &Camera::sensorCenterCrop, DOC(dai, node, Camera, sensorCenterCrop)) .def("setSensorCrop", &Camera::setSensorCrop, py::arg("x"), py::arg("y"), DOC(dai, node, Camera, setSensorCrop)) .def("getSensorCrop", &Camera::getSensorCrop, DOC(dai, node, Camera, getSensorCrop)) .def("getSensorCropX", &Camera::getSensorCropX, DOC(dai, node, Camera, getSensorCropX)) .def("getSensorCropY", &Camera::getSensorCropY, DOC(dai, node, Camera, getSensorCropY)) - .def("setWaitForConfigInput", [](Camera& cam, bool wait){ - // Issue a deprecation warning - PyErr_WarnEx(PyExc_DeprecationWarning, "Use 'inputConfig.setWaitForMessage()' instead", 1); - HEDLEY_DIAGNOSTIC_PUSH - HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED - cam.setWaitForConfigInput(wait); - HEDLEY_DIAGNOSTIC_POP - }, py::arg("wait"), DOC(dai, node, Camera, setWaitForConfigInput)) - - .def("getWaitForConfigInput", [](Camera& cam){ - // Issue a deprecation warning - PyErr_WarnEx(PyExc_DeprecationWarning, "Use 'inputConfig.setWaitForMessage()' instead", 1); - HEDLEY_DIAGNOSTIC_PUSH - HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED - return cam.getWaitForConfigInput(); - HEDLEY_DIAGNOSTIC_POP - }, DOC(dai, node, Camera, getWaitForConfigInput)) - - .def("setPreviewKeepAspectRatio", &Camera::setPreviewKeepAspectRatio, py::arg("keep"), DOC(dai, node, Camera, setPreviewKeepAspectRatio)) - .def("getPreviewKeepAspectRatio", &Camera::getPreviewKeepAspectRatio, DOC(dai, node, Camera, getPreviewKeepAspectRatio)) .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("numerator"), py::arg("denominator"), DOC(dai, node, Camera, setIspScale)) .def("setIspScale", static_cast)>(&Camera::setIspScale), py::arg("scale"), DOC(dai, node, Camera, setIspScale, 2)) .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("horizNum"), py::arg("horizDenom"), py::arg("vertNum"), py::arg("vertDenom"), DOC(dai, node, Camera, setIspScale, 3)) .def("setIspScale", static_cast,std::tuple)>(&Camera::setIspScale), py::arg("horizScale"), py::arg("vertScale"), DOC(dai, node, Camera, setIspScale, 4)) - .def("getIspSize", &Camera::getIspSize, DOC(dai, node, Camera, getIspSize)) - .def("getIspWidth", &Camera::getIspWidth, DOC(dai, node, Camera, getIspWidth)) - .def("getIspHeight", &Camera::getIspHeight, DOC(dai, node, Camera, getIspHeight)) - - .def("setPreviewNumFramesPool", &Camera::setPreviewNumFramesPool, DOC(dai, node, Camera, setPreviewNumFramesPool)) - .def("setVideoNumFramesPool", &Camera::setVideoNumFramesPool, DOC(dai, node, Camera, setVideoNumFramesPool)) - .def("setStillNumFramesPool", &Camera::setStillNumFramesPool, DOC(dai, node, Camera, setStillNumFramesPool)) - .def("setRawNumFramesPool", &Camera::setRawNumFramesPool, DOC(dai, node, Camera, setRawNumFramesPool)) - .def("setIspNumFramesPool", &Camera::setIspNumFramesPool, DOC(dai, node, Camera, setIspNumFramesPool)) - .def("setNumFramesPool", &Camera::setNumFramesPool, py::arg("raw"), py::arg("isp"), py::arg("preview"), py::arg("video"), py::arg("still"), DOC(dai, node, Camera, setNumFramesPool)) - .def("getPreviewNumFramesPool", &Camera::getPreviewNumFramesPool, DOC(dai, node, Camera, getPreviewNumFramesPool)) - .def("getVideoNumFramesPool", &Camera::getVideoNumFramesPool, DOC(dai, node, Camera, getVideoNumFramesPool)) - .def("getStillNumFramesPool", &Camera::getStillNumFramesPool, DOC(dai, node, Camera, getStillNumFramesPool)) - .def("getRawNumFramesPool", &Camera::getRawNumFramesPool, DOC(dai, node, Camera, getRawNumFramesPool)) - .def("getIspNumFramesPool", &Camera::getIspNumFramesPool, DOC(dai, node, Camera, getIspNumFramesPool)) .def("setCamera", &Camera::setCamera, py::arg("name"), DOC(dai, node, Camera, setCamera)) .def("getCamera", &Camera::getCamera, DOC(dai, node, Camera, getCamera)) - .def("setSensorSize", static_cast(&Camera::setSensorSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setSensorSize)) - .def("setSensorSize", static_cast)>(&Camera::setSensorSize), py::arg("size"), DOC(dai, node, Camera, setSensorSize, 2)) + .def("setSize", static_cast(&Camera::setSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setSize)) + .def("setSize", static_cast)>(&Camera::setSize), py::arg("size"), DOC(dai, node, Camera, setSize, 2)) ; // ALIAS From 33744cbad5658fecbba9764078489b7ab15644fc Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 30 Dec 2022 18:15:33 +0100 Subject: [PATCH 27/43] Updated FW with Camera warp capabilities --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index baa24cead..cba0cdae8 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit baa24cead9524c10f7dada7cc28db60a5751737f +Subproject commit cba0cdae8ca53d1da33d83aa97196c59cc5b7021 From 32533fda9f107c9088fe348f4e7549fe20a06109 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 2 Jan 2023 20:18:38 +0100 Subject: [PATCH 28/43] Added span bindings --- src/utility/SpanBindings.hpp | 170 +++++++++++++++++++++++++++++++++++ 1 file changed, 170 insertions(+) create mode 100644 src/utility/SpanBindings.hpp diff --git a/src/utility/SpanBindings.hpp b/src/utility/SpanBindings.hpp new file mode 100644 index 000000000..859f1df31 --- /dev/null +++ b/src/utility/SpanBindings.hpp @@ -0,0 +1,170 @@ +#pragma once + +#include +#include + +#include "depthai/utility/span.hpp" + +namespace pybind11 { +namespace detail { + +template +struct span_name_maker { + template + static constexpr auto make(const T &t) { + return concat(t, span_name_maker::make(t)); + } +}; + +template <> +struct span_name_maker<1> { + template + static constexpr auto make(const T &t) { + return t; + } +}; + +// span with fixed size converts to a tuple +template struct type_caster> { + using span_type = typename dai::span; + using value_conv = make_caster; + using value_type = typename std::remove_cv::type; + + value_type backing_array[Extent] = {}; + + PYBIND11_TYPE_CASTER(span_type, _("Tuple[") + span_name_maker::make(value_conv::name) + _("]")); + + type_caster() : value(backing_array) {} + + bool load(handle src, bool convert) { + if (!isinstance(src) || isinstance(src)) + return false; + auto s = reinterpret_borrow(src); + if (s.size() != Extent) + return false; + size_t i = 0; + for (auto it : s) { + value_conv conv; + if (!conv.load(it, convert)) + return false; + backing_array[i] = cast_op(std::move(conv)); + i++; + } + return true; + } + +public: + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + if (!std::is_lvalue_reference::value) + policy = return_value_policy_override::policy(policy); + tuple l(Extent); + size_t index = 0; + for (auto &&value : src) { + auto value_ = reinterpret_steal( + value_conv::cast(forward_like(value), policy, parent)); + if (!value_) + return handle(); + PyTuple_SET_ITEM(l.ptr(), (ssize_t)index++, + value_.release().ptr()); // steals a reference + } + return l.release(); + } +}; + + +// span with dynamic extent +template struct type_caster> { + using span_type = typename dai::span; + using value_conv = make_caster; + using value_type = typename std::remove_cv::type; + PYBIND11_TYPE_CASTER(span_type, _("List[") + value_conv::name + _("]")); + + std::vector vec; + bool load(handle src, bool convert) { + if (!isinstance(src) || isinstance(src)) + return false; + auto s = reinterpret_borrow(src); + vec.reserve(s.size()); + for (auto it : s) { + value_conv conv; + if (!conv.load(it, convert)) + return false; + vec.push_back(cast_op(std::move(conv))); + } + value = span_type(vec.data(), vec.size()); + return true; + } + +public: + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + if (!std::is_lvalue_reference::value) + policy = return_value_policy_override::policy(policy); + list l(src.size()); + size_t index = 0; + for (auto &&value : src) { + auto value_ = reinterpret_steal( + value_conv::cast(forward_like(value), policy, parent)); + if (!value_) + return handle(); + PyList_SET_ITEM(l.ptr(), (ssize_t)index++, + value_.release().ptr()); // steals a reference + } + return l.release(); + } +}; + +// span specialization: accepts any readonly buffers +template <> struct type_caster> { + using span_type = typename dai::span; + PYBIND11_TYPE_CASTER(span_type, _("buffer")); + + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + auto buf = reinterpret_borrow(src); + auto req = buf.request(); + if (req.ndim != 1) { + return false; + } + + value = span_type((const uint8_t*)req.ptr, req.size*req.itemsize); + return true; + } + +public: + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + return bytes((char*)src.data(), src.size()).release(); + } +}; + +// span specialization: writeable buffer +template <> struct type_caster> { + using span_type = typename dai::span; + PYBIND11_TYPE_CASTER(dai::span, _("buffer")); + + bool load(handle src, bool convert) { + if (!isinstance(src)) + return false; + auto buf = reinterpret_borrow(src); + auto req = buf.request(true); // buffer must be writeable + if (req.ndim != 1) { + return false; + } + + value = dai::span((uint8_t*)req.ptr, req.size*req.itemsize); + return true; + } + +public: + template + static handle cast(T &&src, return_value_policy policy, handle parent) { + // TODO: should this be a memoryview instead? + return bytes((char*)src.data(), src.size()).release(); + } +}; + +} // namespace detail +} // namespace pybind11 \ No newline at end of file From 0516f9273392d6ac829a53fb6441b9480f54a3da Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 2 Jan 2023 20:18:51 +0100 Subject: [PATCH 29/43] Added 'Camera' related bindings --- depthai-core | 2 +- src/pipeline/node/CameraBindings.cpp | 29 +++++++++++++++++++++++++++- src/pybind11_common.hpp | 1 + 3 files changed, 30 insertions(+), 2 deletions(-) diff --git a/depthai-core b/depthai-core index cba0cdae8..4dedea1e2 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit cba0cdae8ca53d1da33d83aa97196c59cc5b7021 +Subproject commit 4dedea1e295008ecb6bc6c1fb4bde02ea62f6d8f diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp index 0e5c935be..194a123cb 100644 --- a/src/pipeline/node/CameraBindings.cpp +++ b/src/pipeline/node/CameraBindings.cpp @@ -12,7 +12,7 @@ void bind_camera(pybind11::module& m, void* pCallstack){ // Node and Properties declare upfront py::class_ cameraProperties(m, "CameraProperties", DOC(dai, CameraProperties)); - // py::enum_ cameraPropertiesSensorResolution(cameraProperties, "SensorResolution", DOC(dai, CameraProperties, SensorResolution)); + py::enum_ cameraPropertiesWarpMeshSource(cameraProperties, "WarpMeshSource", DOC(dai, CameraProperties, WarpMeshSource)); py::enum_ cameraPropertiesColorOrder(cameraProperties, "ColorOrder", DOC(dai, CameraProperties, ColorOrder)); auto camera = ADD_NODE(Camera); @@ -44,6 +44,14 @@ void bind_camera(pybind11::module& m, void* pCallstack){ // .value("THE_800_P", CameraProperties::SensorResolution::THE_800_P) // ; + // Camera Properties - WarpMeshSource + cameraPropertiesWarpMeshSource + .value("AUTO", CameraProperties::WarpMeshSource::AUTO) + .value("NONE", CameraProperties::WarpMeshSource::NONE) + .value("CALIBRATION", CameraProperties::WarpMeshSource::CALIBRATION) + .value("URI", CameraProperties::WarpMeshSource::URI) + ; + cameraPropertiesColorOrder .value("BGR", CameraProperties::ColorOrder::BGR) .value("RGB", CameraProperties::ColorOrder::RGB) @@ -68,11 +76,20 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def_readwrite("sensorCropY", &CameraProperties::sensorCropY) .def_readwrite("previewKeepAspectRatio", &CameraProperties::previewKeepAspectRatio) .def_readwrite("ispScale", &CameraProperties::ispScale) + .def_readwrite("numFramesPoolRaw", &CameraProperties::numFramesPoolRaw) .def_readwrite("numFramesPoolIsp", &CameraProperties::numFramesPoolIsp) .def_readwrite("numFramesPoolVideo", &CameraProperties::numFramesPoolVideo) .def_readwrite("numFramesPoolPreview", &CameraProperties::numFramesPoolPreview) .def_readwrite("numFramesPoolStill", &CameraProperties::numFramesPoolStill) + + .def_readwrite("warpMeshSource", &CameraProperties::warpMeshSource) + .def_readwrite("warpMeshUri", &CameraProperties::warpMeshUri) + .def_readwrite("warpMeshWidth", &CameraProperties::warpMeshWidth) + .def_readwrite("warpMeshHeight", &CameraProperties::warpMeshHeight) + .def_readwrite("calibAlpha", &CameraProperties::calibAlpha) + .def_readwrite("warpMeshStepWidth", &CameraProperties::warpMeshStepWidth) + .def_readwrite("warpMeshStepHeight", &CameraProperties::warpMeshStepHeight) ; // Camera node @@ -129,6 +146,16 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def("setSize", static_cast(&Camera::setSize), py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setSize)) .def("setSize", static_cast)>(&Camera::setSize), py::arg("size"), DOC(dai, node, Camera, setSize, 2)) + + .def("setMeshSource", &Camera::setMeshSource, py::arg("source"), DOC(dai, node, Camera, setMeshSource)) + .def("getMeshSource", &Camera::getMeshSource, DOC(dai, node, Camera, getMeshSource)) + .def("loadMeshFile", &Camera::loadMeshFile, py::arg("warpMesh"), DOC(dai, node, Camera, loadMeshFile)) + .def("loadMeshData", &Camera::loadMeshData, py::arg("warpMesh"), DOC(dai, node, Camera, loadMeshData)) + .def("setMeshStep", &Camera::setMeshStep, py::arg("width"), py::arg("height"), DOC(dai, node, Camera, setMeshStep)) + .def("getMeshStep", &Camera::getMeshStep, DOC(dai, node, Camera, getMeshStep)) + .def("setCalibrationAlpha", &Camera::setCalibrationAlpha, py::arg("alpha"), DOC(dai, node, Camera, setCalibrationAlpha)) + .def("getCalibrationAlpha", &Camera::getCalibrationAlpha, DOC(dai, node, Camera, getCalibrationAlpha)) + ; // ALIAS daiNodeModule.attr("Camera").attr("Properties") = cameraProperties; diff --git a/src/pybind11_common.hpp b/src/pybind11_common.hpp index 6dbc0967b..6478ae5e2 100644 --- a/src/pybind11_common.hpp +++ b/src/pybind11_common.hpp @@ -13,6 +13,7 @@ #include #include #include +#include // Include docstring file #include "docstring.hpp" From b7556a9141e4339034a3adcb0f6372c8dca7de45 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 3 Jan 2023 13:42:30 +0200 Subject: [PATCH 30/43] Update core --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index cea13d673..84e163df1 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit cea13d673d15712d8c058ae2d69095f1c5d66a1a +Subproject commit 84e163df17121cf2879ac9fe39ff877d2fd4054d From 9ca3b408ea1b51be27d246fb250349c574200134 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 5 Jan 2023 14:38:57 +0100 Subject: [PATCH 31/43] FW - Modifed watchdog to do a graceful reset instead --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 84e163df1..b2da50897 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 84e163df17121cf2879ac9fe39ff877d2fd4054d +Subproject commit b2da50897224ca1bcd5d6ad8ae0d04b798904fad From 0a45ec92aa927eaaf238f2b022db1669713f44d5 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Sun, 8 Jan 2023 10:37:57 +0100 Subject: [PATCH 32/43] Added additional API to retrieve timestamps at various exposure points --- depthai-core | 2 +- src/pipeline/datatype/ImgFrameBindings.cpp | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 84e163df1..06b7befea 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 84e163df17121cf2879ac9fe39ff877d2fd4054d +Subproject commit 06b7befeaa4d5424b5511100e3042db3723f5a4b diff --git a/src/pipeline/datatype/ImgFrameBindings.cpp b/src/pipeline/datatype/ImgFrameBindings.cpp index ee867395b..bf5ccbea3 100644 --- a/src/pipeline/datatype/ImgFrameBindings.cpp +++ b/src/pipeline/datatype/ImgFrameBindings.cpp @@ -119,6 +119,10 @@ void bind_imgframe(pybind11::module& m, void* pCallstack){ // getters .def("getTimestamp", &ImgFrame::getTimestamp, DOC(dai, ImgFrame, getTimestamp)) .def("getTimestampDevice", &ImgFrame::getTimestampDevice, DOC(dai, ImgFrame, getTimestampDevice)) + .def("getTimestampExposureMiddle", &ImgFrame::getTimestampExposureMiddle, DOC(dai, ImgFrame, getTimestampExposureMiddle)) + .def("getTimestampDeviceExposureMiddle", &ImgFrame::getTimestampDeviceExposureMiddle, DOC(dai, ImgFrame, getTimestampDeviceExposureMiddle)) + .def("getTimestampExposureStart", &ImgFrame::getTimestampExposureStart, DOC(dai, ImgFrame, getTimestampExposureStart)) + .def("getTimestampDeviceExposureStart", &ImgFrame::getTimestampDeviceExposureStart, DOC(dai, ImgFrame, getTimestampDeviceExposureStart)) .def("getInstanceNum", &ImgFrame::getInstanceNum, DOC(dai, ImgFrame, getInstanceNum)) .def("getCategory", &ImgFrame::getCategory, DOC(dai, ImgFrame, getCategory)) .def("getSequenceNum", &ImgFrame::getSequenceNum, DOC(dai, ImgFrame, getSequenceNum)) From 1d25275f743b942c2b3707d1576f9ef45c38253b Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 12 Jan 2023 02:48:47 +0100 Subject: [PATCH 33/43] WIP: mockIsp capabilities --- depthai-core | 2 +- examples/Camera/camera_preview.py | 2 +- .../disparity_colormap_encoding.py | 62 +++++++++++++++++++ src/pipeline/node/CameraBindings.cpp | 1 + 4 files changed, 65 insertions(+), 2 deletions(-) create mode 100755 examples/VideoEncoder/disparity_colormap_encoding.py diff --git a/depthai-core b/depthai-core index 4dedea1e2..fec218ecf 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 4dedea1e295008ecb6bc6c1fb4bde02ea62f6d8f +Subproject commit fec218ecf14930b271a7a29aa60af08147d0fcf1 diff --git a/examples/Camera/camera_preview.py b/examples/Camera/camera_preview.py index 5516b19a8..ba9aa108a 100755 --- a/examples/Camera/camera_preview.py +++ b/examples/Camera/camera_preview.py @@ -5,7 +5,7 @@ import time # Connect to device and start pipeline -with dai.Device(dai.OpenVINO.VERSION_2021_1, dai.UsbSpeed.SUPER_PLUS) as device: +with dai.Device(dai.OpenVINO.DEFAULT_VERSION, dai.UsbSpeed.SUPER_PLUS) as device: # Device name print('Device name:', device.getDeviceName()) # Bootloader version diff --git a/examples/VideoEncoder/disparity_colormap_encoding.py b/examples/VideoEncoder/disparity_colormap_encoding.py new file mode 100755 index 000000000..5f69dba5c --- /dev/null +++ b/examples/VideoEncoder/disparity_colormap_encoding.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python3 + +import depthai as dai + +# Create pipeline +pipeline = dai.Pipeline() + +# Create left/right mono cameras for Stereo depth +monoLeft = pipeline.create(dai.node.MonoCamera) +monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoLeft.setBoardSocket(dai.CameraBoardSocket.LEFT) + +monoRight = pipeline.create(dai.node.MonoCamera) +monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P) +monoRight.setBoardSocket(dai.CameraBoardSocket.RIGHT) + +# Create a node that will produce the depth map +depth = pipeline.create(dai.node.StereoDepth) +depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY) +depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7) +depth.setLeftRightCheck(False) +depth.setExtendedDisparity(False) +# Subpixel disparity is of UINT16 format, which is unsupported by VideoEncoder +depth.setSubpixel(False) +monoLeft.out.link(depth.left) +monoRight.out.link(depth.right) + +# Colormap +colormap = pipeline.create(dai.node.ImageManip) +colormap.initialConfig.setColormap(dai.Colormap.TURBO, 0, 95) +colormap.initialConfig.setFrameType(dai.ImgFrame.Type.NV12) + +videoEnc = pipeline.create(dai.node.VideoEncoder) +# Depth resolution/FPS will be the same as mono resolution/FPS +videoEnc.setDefaultProfilePreset(monoLeft.getFps(), dai.VideoEncoderProperties.Profile.H264_HIGH) + +# Link +depth.disparity.link(colormap.inputImage) +colormap.out.link(videoEnc.input) + +xout = pipeline.create(dai.node.XLinkOut) +xout.setStreamName("enc") +videoEnc.bitstream.link(xout.input) + +# Connect to device and start pipeline +with dai.Device(pipeline) as device: + + # Output queue will be used to get the encoded data from the output defined above + q = device.getOutputQueue(name="enc") + + # The .h265 file is a raw stream file (not playable yet) + with open('disparity.h264', 'wb') as videoFile: + print("Press Ctrl+C to stop encoding...") + try: + while True: + videoFile.write(q.get().getData()) + except KeyboardInterrupt: + # Keyboard interrupt (Ctrl + C) detected + pass + + print("To view the encoded data, convert the stream file (.mjpeg) into a video file (.mp4) using a command below:") + print("ffmpeg -framerate 30 -i disparity.mjpeg -c copy video.mp4") diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp index 194a123cb..60a7640b8 100644 --- a/src/pipeline/node/CameraBindings.cpp +++ b/src/pipeline/node/CameraBindings.cpp @@ -103,6 +103,7 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def_readonly("isp", &Camera::isp, DOC(dai, node, Camera, isp)) .def_readonly("raw", &Camera::raw, DOC(dai, node, Camera, raw)) .def_readonly("frameEvent", &Camera::frameEvent, DOC(dai, node, Camera, frameEvent)) + .def_readonly("mockIsp", &Camera::mockIsp, DOC(dai, node, Camera, mockIsp)) .def("setBoardSocket", &Camera::setBoardSocket, py::arg("boardSocket"), DOC(dai, node, Camera, setBoardSocket)) .def("getBoardSocket", &Camera::getBoardSocket, DOC(dai, node, Camera, getBoardSocket)) .def("setImageOrientation", &Camera::setImageOrientation, py::arg("imageOrientation"), DOC(dai, node, Camera, setImageOrientation)) From 87ff67c838f9c981d7ceb117a0af938eb64d4751 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 12 Jan 2023 03:21:40 +0100 Subject: [PATCH 34/43] [FW] Fix for CAM_C not being detected --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index d60786147..efb3f4ddc 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit d607861477507c28bcdee21198372a4cdc9a374d +Subproject commit efb3f4ddc8bc378974853e1dd341a8b3251553a4 From ef31c11057532e9f3289acd7f1a4b4d48c81657a Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 13 Jan 2023 21:41:46 +0100 Subject: [PATCH 35/43] Device - Added non exclusive boot option --- depthai-core | 2 +- examples/device/device_all_boot_bootloader.py | 6 ++++++ examples/device/device_boot_non_exclusive.py | 10 ++++++++++ src/DeviceBindings.cpp | 1 + 4 files changed, 18 insertions(+), 1 deletion(-) create mode 100644 examples/device/device_all_boot_bootloader.py create mode 100644 examples/device/device_boot_non_exclusive.py diff --git a/depthai-core b/depthai-core index efb3f4ddc..85e90ccce 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit efb3f4ddc8bc378974853e1dd341a8b3251553a4 +Subproject commit 85e90ccce390dae4d65e21fde11856ede7e71641 diff --git a/examples/device/device_all_boot_bootloader.py b/examples/device/device_all_boot_bootloader.py new file mode 100644 index 000000000..4c2e9a56b --- /dev/null +++ b/examples/device/device_all_boot_bootloader.py @@ -0,0 +1,6 @@ +import depthai as dai + +devices = dai.Device.getAllConnectedDevices() + +for device in devices: + dai.XLinkConnection.bootBootloader(device) diff --git a/examples/device/device_boot_non_exclusive.py b/examples/device/device_boot_non_exclusive.py new file mode 100644 index 000000000..898b292f6 --- /dev/null +++ b/examples/device/device_boot_non_exclusive.py @@ -0,0 +1,10 @@ +import depthai as dai +import time + +cfg = dai.Device.Config() +cfg.nonExclusiveMode = True + +with dai.Device(cfg) as device: + while not device.isClosed(): + print('CPU usage:',device.getLeonCssCpuUsage().average) + time.sleep(1) \ No newline at end of file diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 43efada81..85179e279 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -459,6 +459,7 @@ void DeviceBindings::bind(pybind11::module& m, void* pCallstack){ .def(py::init<>()) .def_readwrite("version", &Device::Config::version) .def_readwrite("board", &Device::Config::board) + .def_readwrite("nonExclusiveMode", &Device::Config::nonExclusiveMode) ; // Bind constructors From 164e6cc414bf2c453f752de2654b8112abb66918 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sun, 15 Jan 2023 20:06:33 +0100 Subject: [PATCH 36/43] Slight Colormap API improvements --- depthai-core | 2 +- examples/StereoDepth/depth_colormap.py | 2 +- .../disparity_colormap_encoding.py | 2 +- src/pipeline/CommonBindings.cpp | 42 ++++++++++--------- .../datatype/ImageManipConfigBindings.cpp | 4 +- 5 files changed, 28 insertions(+), 24 deletions(-) diff --git a/depthai-core b/depthai-core index fec218ecf..66c8065cd 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit fec218ecf14930b271a7a29aa60af08147d0fcf1 +Subproject commit 66c8065cd84607a1c9dff706dab6710458e81703 diff --git a/examples/StereoDepth/depth_colormap.py b/examples/StereoDepth/depth_colormap.py index b334ffb34..05d86f85c 100755 --- a/examples/StereoDepth/depth_colormap.py +++ b/examples/StereoDepth/depth_colormap.py @@ -38,7 +38,7 @@ # Create a colormap colormap = pipeline.create(dai.node.ImageManip) -colormap.initialConfig.setColormap(dai.Colormap.TURBO, 0, 95) +colormap.initialConfig.setColormap(dai.Colormap.STEREO_TURBO, depth.initialConfig.getMaxDisparity()) colormap.initialConfig.setFrameType(dai.ImgFrame.Type.NV12) # Linking diff --git a/examples/VideoEncoder/disparity_colormap_encoding.py b/examples/VideoEncoder/disparity_colormap_encoding.py index 5f69dba5c..09d602b10 100755 --- a/examples/VideoEncoder/disparity_colormap_encoding.py +++ b/examples/VideoEncoder/disparity_colormap_encoding.py @@ -27,7 +27,7 @@ # Colormap colormap = pipeline.create(dai.node.ImageManip) -colormap.initialConfig.setColormap(dai.Colormap.TURBO, 0, 95) +colormap.initialConfig.setColormap(dai.Colormap.TURBO, depth.initialConfig.getMaxDisparity()) colormap.initialConfig.setFrameType(dai.ImgFrame.Type.NV12) videoEnc = pipeline.create(dai.node.VideoEncoder) diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 9c1602f74..4c3c47512 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -294,28 +294,30 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ colormap .value("NONE", Colormap::NONE) - .value("AUTUMN", Colormap::AUTUMN) - .value("BONE", Colormap::BONE) .value("JET", Colormap::JET) - .value("WINTER", Colormap::WINTER) - .value("RAINBOW", Colormap::RAINBOW) - .value("OCEAN", Colormap::OCEAN) - .value("SUMMER", Colormap::SUMMER) - .value("SPRING", Colormap::SPRING) - .value("COOL", Colormap::COOL) - .value("HSV", Colormap::HSV) - .value("PINK", Colormap::PINK) - .value("HOT", Colormap::HOT) - .value("PARULA", Colormap::PARULA) - .value("MAGMA", Colormap::MAGMA) - .value("INFERNO", Colormap::INFERNO) - .value("PLASMA", Colormap::PLASMA) - .value("VIRIDIS", Colormap::VIRIDIS) - .value("CIVIDIS", Colormap::CIVIDIS) - .value("TWILIGHT", Colormap::TWILIGHT) - .value("TWILIGHT_SHIFTED", Colormap::TWILIGHT_SHIFTED) .value("TURBO", Colormap::TURBO) - .value("DEEPGREEN", Colormap::DEEPGREEN) + .value("STEREO_JET", Colormap::STEREO_JET) + .value("STEREO_TURBO", Colormap::STEREO_TURBO) + // .value("AUTUMN", Colormap::AUTUMN) + // .value("BONE", Colormap::BONE) + // .value("WINTER", Colormap::WINTER) + // .value("RAINBOW", Colormap::RAINBOW) + // .value("OCEAN", Colormap::OCEAN) + // .value("SUMMER", Colormap::SUMMER) + // .value("SPRING", Colormap::SPRING) + // .value("COOL", Colormap::COOL) + // .value("HSV", Colormap::HSV) + // .value("PINK", Colormap::PINK) + // .value("HOT", Colormap::HOT) + // .value("PARULA", Colormap::PARULA) + // .value("MAGMA", Colormap::MAGMA) + // .value("INFERNO", Colormap::INFERNO) + // .value("PLASMA", Colormap::PLASMA) + // .value("VIRIDIS", Colormap::VIRIDIS) + // .value("CIVIDIS", Colormap::CIVIDIS) + // .value("TWILIGHT", Colormap::TWILIGHT) + // .value("TWILIGHT_SHIFTED", Colormap::TWILIGHT_SHIFTED) + // .value("DEEPGREEN", Colormap::DEEPGREEN) ; } diff --git a/src/pipeline/datatype/ImageManipConfigBindings.cpp b/src/pipeline/datatype/ImageManipConfigBindings.cpp index 05b3f38c2..847d69d5a 100644 --- a/src/pipeline/datatype/ImageManipConfigBindings.cpp +++ b/src/pipeline/datatype/ImageManipConfigBindings.cpp @@ -112,7 +112,9 @@ void bind_imagemanipconfig(pybind11::module& m, void* pCallstack){ .def("setResizeThumbnail", static_cast(&ImageManipConfig::setResizeThumbnail), py::arg("w"), py::arg("h"), py::arg("bgRed")=0, py::arg("bgGreen")=0, py::arg("bgBlue")=0, DOC(dai, ImageManipConfig, setResizeThumbnail)) .def("setResizeThumbnail", static_cast, int, int, int)>(&ImageManipConfig::setResizeThumbnail), py::arg("size"), py::arg("bgRed")=0, py::arg("bgGreen")=0, py::arg("bgBlue")=0, DOC(dai, ImageManipConfig, setResizeThumbnail, 2)) .def("setFrameType", &ImageManipConfig::setFrameType, py::arg("type"), DOC(dai, ImageManipConfig, setFrameType)) - .def("setColormap", &ImageManipConfig::setColormap, py::arg("colormap"), py::arg("min") = 0, py::arg("max") = 255, DOC(dai, ImageManipConfig, setColormap)) + .def("setColormap", static_cast(&ImageManipConfig::setColormap), py::arg("colormap"), py::arg("min"), py::arg("max"), DOC(dai, ImageManipConfig, setColormap)) + .def("setColormap", static_cast(&ImageManipConfig::setColormap), py::arg("colormap"), py::arg("max") = 255, DOC(dai, ImageManipConfig, setColormap)) + .def("setColormap", static_cast(&ImageManipConfig::setColormap), py::arg("colormap"), py::arg("max") = 255.0f, DOC(dai, ImageManipConfig, setColormap)) .def("setHorizontalFlip", &ImageManipConfig::setHorizontalFlip, py::arg("flip"), DOC(dai, ImageManipConfig, setHorizontalFlip)) .def("setVerticalFlip", &ImageManipConfig::setVerticalFlip, py::arg("flip"), DOC(dai, ImageManipConfig, setVerticalFlip)) .def("setReusePreviousImage", &ImageManipConfig::setReusePreviousImage, py::arg("reuse"), DOC(dai, ImageManipConfig, setReusePreviousImage)) From 98801478d90acdc38a30884415a5f10a23d1b62f Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 17 Jan 2023 14:21:48 +0100 Subject: [PATCH 37/43] Added DeviceBase convinience constructors taking name or deviceid as string --- depthai-core | 2 +- src/DeviceBindings.cpp | 14 ++++++++++++-- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/depthai-core b/depthai-core index d60786147..dfecb75d4 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit d607861477507c28bcdee21198372a4cdc9a374d +Subproject commit dfecb75d4fcc5f84a9fa7ee832582dbc1c5c36af diff --git a/src/DeviceBindings.cpp b/src/DeviceBindings.cpp index 43efada81..5bfb8126d 100644 --- a/src/DeviceBindings.cpp +++ b/src/DeviceBindings.cpp @@ -289,14 +289,24 @@ static void bindConstructors(ARG& arg){ }), py::arg("config"), py::arg("deviceInfo"), DOC(dai, DeviceBase, DeviceBase, 19)) // DeviceInfo version - .def(py::init([](const DeviceInfo& deviceInfo){ + .def(py::init([](const DeviceInfo& deviceInfo){ py::gil_scoped_release release; return std::make_unique(deviceInfo); }), py::arg("deviceInfo"), DOC(dai, DeviceBase, DeviceBase, 20)) - .def(py::init([](const DeviceInfo& deviceInfo, UsbSpeed maxUsbSpeed){ + .def(py::init([](const DeviceInfo& deviceInfo, UsbSpeed maxUsbSpeed){ py::gil_scoped_release release; return std::make_unique(deviceInfo, maxUsbSpeed); }), py::arg("deviceInfo"), py::arg("maxUsbSpeed"), DOC(dai, DeviceBase, DeviceBase, 21)) + + // name or device id version + .def(py::init([](std::string nameOrDeviceId){ + py::gil_scoped_release release; + return std::make_unique(std::move(nameOrDeviceId)); + }), py::arg("nameOrDeviceId"), DOC(dai, DeviceBase, DeviceBase, 22)) + .def(py::init([](std::string nameOrDeviceId, UsbSpeed maxUsbSpeed){ + py::gil_scoped_release release; + return std::make_unique(std::move(nameOrDeviceId), maxUsbSpeed); + }), py::arg("nameOrDeviceId"), py::arg("maxUsbSpeed"), DOC(dai, DeviceBase, DeviceBase, 23)) ; } From f90eed9a3af09a0c43c36e0383c095ef4786fe4e Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Wed, 18 Jan 2023 16:04:58 +0100 Subject: [PATCH 38/43] Camera - Disabled some of the functionality for now --- depthai-core | 2 +- examples/Camera/camera_isp.py | 62 ++++++++++++++++++++++++++++ src/pipeline/node/CameraBindings.cpp | 22 +++++----- 3 files changed, 74 insertions(+), 12 deletions(-) create mode 100755 examples/Camera/camera_isp.py diff --git a/depthai-core b/depthai-core index 66c8065cd..1e9d2124b 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 66c8065cd84607a1c9dff706dab6710458e81703 +Subproject commit 1e9d2124b168b04ef9f00b4ca9321aabd57a305e diff --git a/examples/Camera/camera_isp.py b/examples/Camera/camera_isp.py new file mode 100755 index 000000000..5173d56e9 --- /dev/null +++ b/examples/Camera/camera_isp.py @@ -0,0 +1,62 @@ +#!/usr/bin/env python3 + +import cv2 +import depthai as dai +import time + +# Connect to device and start pipeline +with dai.Device() as device: + # Device name + print('Device name:', device.getDeviceName()) + # Bootloader version + if device.getBootloaderVersion() is not None: + print('Bootloader version:', device.getBootloaderVersion()) + # Print out usb speed + print('Usb speed:', device.getUsbSpeed().name) + # Connected cameras + print('Connected cameras:', device.getConnectedCameraFeatures()) + + # Create pipeline + pipeline = dai.Pipeline() + cams = device.getConnectedCameraFeatures() + streams = [] + for cam in cams: + print(str(cam), str(cam.socket), cam.socket) + c = pipeline.create(dai.node.Camera) + x = pipeline.create(dai.node.XLinkOut) + c.isp.link(x.input) + c.setBoardSocket(cam.socket) + stream = str(cam.socket) + if cam.name: + stream = f'{cam.name} ({stream})' + x.setStreamName(stream) + streams.append(stream) + + # Start pipeline + device.startPipeline(pipeline) + fpsCounter = {} + lastFpsCount = {} + tfps = time.time() + while not device.isClosed(): + queueNames = device.getQueueEvents(streams) + for stream in queueNames: + messages = device.getOutputQueue(stream).tryGetAll() + fpsCounter[stream] = fpsCounter.get(stream, 0.0) + len(messages) + for message in messages: + # Display arrived frames + if type(message) == dai.ImgFrame: + # render fps + fps = lastFpsCount.get(stream, 0) + frame = message.getCvFrame() + cv2.putText(frame, "Fps: {:.2f}".format(fps), (10, 10), cv2.FONT_HERSHEY_TRIPLEX, 0.4, (255,255,255)) + cv2.imshow(stream, frame) + + if time.time() - tfps >= 1.0: + scale = time.time() - tfps + for stream in fpsCounter.keys(): + lastFpsCount[stream] = fpsCounter[stream] / scale + fpsCounter = {} + tfps = time.time() + + if cv2.waitKey(1) == ord('q'): + break diff --git a/src/pipeline/node/CameraBindings.cpp b/src/pipeline/node/CameraBindings.cpp index 60a7640b8..421d0a7b9 100644 --- a/src/pipeline/node/CameraBindings.cpp +++ b/src/pipeline/node/CameraBindings.cpp @@ -103,7 +103,7 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def_readonly("isp", &Camera::isp, DOC(dai, node, Camera, isp)) .def_readonly("raw", &Camera::raw, DOC(dai, node, Camera, raw)) .def_readonly("frameEvent", &Camera::frameEvent, DOC(dai, node, Camera, frameEvent)) - .def_readonly("mockIsp", &Camera::mockIsp, DOC(dai, node, Camera, mockIsp)) + // .def_readonly("mockIsp", &Camera::mockIsp, DOC(dai, node, Camera, mockIsp)) .def("setBoardSocket", &Camera::setBoardSocket, py::arg("boardSocket"), DOC(dai, node, Camera, setBoardSocket)) .def("getBoardSocket", &Camera::getBoardSocket, DOC(dai, node, Camera, getBoardSocket)) .def("setImageOrientation", &Camera::setImageOrientation, py::arg("imageOrientation"), DOC(dai, node, Camera, setImageOrientation)) @@ -130,16 +130,16 @@ void bind_camera(pybind11::module& m, void* pCallstack){ .def("getSize", &Camera::getSize, DOC(dai, node, Camera, getSize)) .def("getWidth", &Camera::getWidth, DOC(dai, node, Camera, getWidth)) .def("getHeight", &Camera::getHeight, DOC(dai, node, Camera, getHeight)) - .def("sensorCenterCrop", &Camera::sensorCenterCrop, DOC(dai, node, Camera, sensorCenterCrop)) - .def("setSensorCrop", &Camera::setSensorCrop, py::arg("x"), py::arg("y"), DOC(dai, node, Camera, setSensorCrop)) - .def("getSensorCrop", &Camera::getSensorCrop, DOC(dai, node, Camera, getSensorCrop)) - .def("getSensorCropX", &Camera::getSensorCropX, DOC(dai, node, Camera, getSensorCropX)) - .def("getSensorCropY", &Camera::getSensorCropY, DOC(dai, node, Camera, getSensorCropY)) - - .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("numerator"), py::arg("denominator"), DOC(dai, node, Camera, setIspScale)) - .def("setIspScale", static_cast)>(&Camera::setIspScale), py::arg("scale"), DOC(dai, node, Camera, setIspScale, 2)) - .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("horizNum"), py::arg("horizDenom"), py::arg("vertNum"), py::arg("vertDenom"), DOC(dai, node, Camera, setIspScale, 3)) - .def("setIspScale", static_cast,std::tuple)>(&Camera::setIspScale), py::arg("horizScale"), py::arg("vertScale"), DOC(dai, node, Camera, setIspScale, 4)) + // .def("sensorCenterCrop", &Camera::sensorCenterCrop, DOC(dai, node, Camera, sensorCenterCrop)) + // .def("setSensorCrop", &Camera::setSensorCrop, py::arg("x"), py::arg("y"), DOC(dai, node, Camera, setSensorCrop)) + // .def("getSensorCrop", &Camera::getSensorCrop, DOC(dai, node, Camera, getSensorCrop)) + // .def("getSensorCropX", &Camera::getSensorCropX, DOC(dai, node, Camera, getSensorCropX)) + // .def("getSensorCropY", &Camera::getSensorCropY, DOC(dai, node, Camera, getSensorCropY)) + + // .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("numerator"), py::arg("denominator"), DOC(dai, node, Camera, setIspScale)) + // .def("setIspScale", static_cast)>(&Camera::setIspScale), py::arg("scale"), DOC(dai, node, Camera, setIspScale, 2)) + // .def("setIspScale", static_cast(&Camera::setIspScale), py::arg("horizNum"), py::arg("horizDenom"), py::arg("vertNum"), py::arg("vertDenom"), DOC(dai, node, Camera, setIspScale, 3)) + // .def("setIspScale", static_cast,std::tuple)>(&Camera::setIspScale), py::arg("horizScale"), py::arg("vertScale"), DOC(dai, node, Camera, setIspScale, 4)) .def("setCamera", &Camera::setCamera, py::arg("name"), DOC(dai, node, Camera, setCamera)) .def("getCamera", &Camera::getCamera, DOC(dai, node, Camera, getCamera)) From 7ff599b97fc513caeb716037435d513991efc572 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Fri, 20 Jan 2023 14:09:14 +0100 Subject: [PATCH 39/43] Tweaked getTimestamp & exposure offset API --- depthai-core | 2 +- src/pipeline/CommonBindings.cpp | 7 +++++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 7cb60d4e3..c12ce3335 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 7cb60d4e3fa5abe6f5a4f55b684fcd81493959b6 +Subproject commit c12ce33350c2dacd9d300756676c0fa6ad20ff52 diff --git a/src/pipeline/CommonBindings.cpp b/src/pipeline/CommonBindings.cpp index 2f8c346bc..1d1558ec6 100644 --- a/src/pipeline/CommonBindings.cpp +++ b/src/pipeline/CommonBindings.cpp @@ -22,6 +22,7 @@ // depthai #include "depthai/common/CameraFeatures.hpp" +#include "depthai/common/CameraExposureOffset.hpp" void CommonBindings::bind(pybind11::module& m, void* pCallstack){ @@ -50,6 +51,7 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ py::class_ detectionParserOptions(m, "DetectionParserOptions", DOC(dai, DetectionParserOptions)); py::class_ rotatedRect(m, "RotatedRect", DOC(dai, RotatedRect)); py::class_ rect(m, "Rect", DOC(dai, Rect)); + py::enum_ cameraExposureOffset(m, "CameraExposureOffset"); /////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////// @@ -290,4 +292,9 @@ void CommonBindings::bind(pybind11::module& m, void* pCallstack){ .def_readwrite("iouThreshold", &DetectionParserOptions::iouThreshold) ; + cameraExposureOffset + .value("START", CameraExposureOffset::START) + .value("MIDDLE", CameraExposureOffset::MIDDLE) + .value("END", CameraExposureOffset::END) + ; } From 9740db602a7b616780e448ae383fd1aea2cbafda Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 13 Dec 2022 05:39:33 +0200 Subject: [PATCH 40/43] FW: IMX296 support, add THE_1440x1080 resolution --- depthai-core | 2 +- src/pipeline/node/ColorCameraBindings.cpp | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 4031f85ed..de8136f02 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 4031f85edcc9012e9275ac433fd180c492c62e7f +Subproject commit de8136f02865f15c01fbf10e3bfe2de7d2c4dfc2 diff --git a/src/pipeline/node/ColorCameraBindings.cpp b/src/pipeline/node/ColorCameraBindings.cpp index cd39b8cc3..143e3c5ff 100644 --- a/src/pipeline/node/ColorCameraBindings.cpp +++ b/src/pipeline/node/ColorCameraBindings.cpp @@ -42,6 +42,7 @@ void bind_colorcamera(pybind11::module& m, void* pCallstack){ .value("THE_48_MP", ColorCameraProperties::SensorResolution::THE_48_MP) .value("THE_720_P", ColorCameraProperties::SensorResolution::THE_720_P) .value("THE_800_P", ColorCameraProperties::SensorResolution::THE_800_P) + .value("THE_1440X1080", ColorCameraProperties::SensorResolution::THE_1440X1080) ; colorCameraPropertiesColorOrder From b04d2dfae4adfc6eba0a22c87a133619ec87ba26 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 10 Nov 2022 18:36:29 +0200 Subject: [PATCH 41/43] cam_test.py: add `-tun`/`--camera-tuning` option --- utilities/cam_test.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/utilities/cam_test.py b/utilities/cam_test.py index 36456584a..58fb20bc8 100755 --- a/utilities/cam_test.py +++ b/utilities/cam_test.py @@ -41,6 +41,7 @@ import collections import time from itertools import cycle +from pathlib import Path def socket_type_pair(arg): socket, type = arg.split(',') @@ -66,6 +67,8 @@ def socket_type_pair(arg): help="Downscale the ISP output by this factor") parser.add_argument('-rs', '--resizable-windows', action='store_true', help="Make OpenCV windows resizable. Note: may introduce some artifacts") +parser.add_argument('-tun', '--camera-tuning', type=Path, + help="Path to custom camera tuning database") args = parser.parse_args() cam_list = [] @@ -174,11 +177,8 @@ def get(self): cam[c].setImageOrientation(dai.CameraImageOrientation.ROTATE_180_DEG) cam[c].setFps(args.fps) -if 0: - print("=== Using custom camera tuning, and limiting RGB FPS to 10") - pipeline.setCameraTuningBlobPath("/home/user/Downloads/tuning_color_low_light.bin") - # TODO: change sensor driver to make FPS automatic (based on requested exposure time) - cam['rgb'].setFps(10) +if args.camera_tuning: + pipeline.setCameraTuningBlobPath(str(args.camera_tuning)) # Pipeline is defined, now we can connect to the device with dai.Device(pipeline) as device: From 125b025cf89ea7ca549f0909d29768c7745d3bca Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Fri, 20 Jan 2023 19:06:03 +0200 Subject: [PATCH 42/43] FW: IMX296 Camera node, IMX378 1080p limited to 60fps --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index de8136f02..34c4b2fe6 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit de8136f02865f15c01fbf10e3bfe2de7d2c4dfc2 +Subproject commit 34c4b2fe6d497f70dd3d4551b5e20abd0a3ae466 From 8e5b54741c8ef506a1542f987230def70847ed2e Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sat, 21 Jan 2023 00:04:14 +0100 Subject: [PATCH 43/43] Bump version to 2.20.0.0 --- depthai-core | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/depthai-core b/depthai-core index 34c4b2fe6..48484a573 160000 --- a/depthai-core +++ b/depthai-core @@ -1 +1 @@ -Subproject commit 34c4b2fe6d497f70dd3d4551b5e20abd0a3ae466 +Subproject commit 48484a5731b99699461c6ca34317063ba6ea2608