From b3a1c3bee3a51235120bfb592d2c0aceadbefdad Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 28 Mar 2023 04:00:00 +0300 Subject: [PATCH 01/63] Update FW: support for configurable ImageManip interpolation type --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/datatype/ImageManipConfig.hpp | 10 ++++++++++ shared/depthai-shared | 2 +- src/pipeline/datatype/ImageManipConfig.cpp | 9 +++++++++ 4 files changed, 21 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index e68cfda1a..2a8d4eb71 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "0ac7686c9827bbca3e35b62437c8dd1a9a64b9e7") +set(DEPTHAI_DEVICE_SIDE_COMMIT "45a89f8644568e03fbfa92f9262bc2f926bd5701") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/datatype/ImageManipConfig.hpp b/include/depthai/pipeline/datatype/ImageManipConfig.hpp index aeab52c8f..521145316 100644 --- a/include/depthai/pipeline/datatype/ImageManipConfig.hpp +++ b/include/depthai/pipeline/datatype/ImageManipConfig.hpp @@ -29,6 +29,7 @@ class ImageManipConfig : public Buffer { using CropConfig = RawImageManipConfig::CropConfig; using ResizeConfig = RawImageManipConfig::ResizeConfig; using FormatConfig = RawImageManipConfig::FormatConfig; + using Interpolation = RawImageManipConfig::Interpolation; /// Construct ImageManipConfig message ImageManipConfig(); @@ -187,6 +188,12 @@ class ImageManipConfig : public Buffer { */ ImageManipConfig& setKeepAspectRatio(bool keep); + /** + * Specify which interpolation method to use + * @param interpolation type of interpolation + */ + ImageManipConfig& setInterpolation(RawImageManipConfig::Interpolation interpolation); + // Functions to retrieve properties /** * @returns Top left X coordinate of crop region @@ -242,6 +249,9 @@ class ImageManipConfig : public Buffer { * @returns specified colormap */ Colormap getColormap() const; + + /// Retrieve which interpolation method to use + RawImageManipConfig::Interpolation getInterpolation() const; }; } // namespace dai diff --git a/shared/depthai-shared b/shared/depthai-shared index aa3e0564c..2d72c8b01 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit aa3e0564c0de3ef66cb6b240ff2b65ed3ed70aba +Subproject commit 2d72c8b01898f28b53128541ceccdf6aafb940fb diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index 38c2236ff..ca1f33bbc 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -234,6 +234,11 @@ ImageManipConfig& ImageManipConfig::setKeepAspectRatio(bool keep) { return *this; } +ImageManipConfig& ImageManipConfig::setInterpolation(RawImageManipConfig::Interpolation interpolation) { + cfg.interpolation = interpolation; + return *this; +} + // Functions to retrieve properties float ImageManipConfig::getCropXMin() const { return cfg.cropConfig.cropRect.xmin; @@ -279,4 +284,8 @@ dai::Colormap ImageManipConfig::getColormap() const { return cfg.formatConfig.colormap; } +RawImageManipConfig::Interpolation ImageManipConfig::getInterpolation() const { + return cfg.interpolation; +} + } // namespace dai From 9be2ff9d7048758291f2fd45e39898e04b2d84c1 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 31 Mar 2023 19:17:51 +0300 Subject: [PATCH 02/63] Update API to use dai::Interpolation --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- examples/Warp/warp_mesh.cpp | 4 ++-- include/depthai/pipeline/datatype/ImageManipConfig.hpp | 5 ++--- include/depthai/pipeline/node/Warp.hpp | 4 ++-- shared/depthai-shared | 2 +- src/pipeline/datatype/ImageManipConfig.cpp | 4 ++-- src/pipeline/node/Warp.cpp | 4 ++-- 7 files changed, 12 insertions(+), 13 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 2a8d4eb71..c9aff926d 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "45a89f8644568e03fbfa92f9262bc2f926bd5701") +set(DEPTHAI_DEVICE_SIDE_COMMIT "d8b7d82704375e9d66ce08f15eab856fdcc785f8") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/Warp/warp_mesh.cpp b/examples/Warp/warp_mesh.cpp index 50228fac1..66ebcbc62 100644 --- a/examples/Warp/warp_mesh.cpp +++ b/examples/Warp/warp_mesh.cpp @@ -27,7 +27,7 @@ int main() { constexpr std::tuple WARP1_OUTPUT_FRAME_SIZE = {992, 500}; warp1->setOutputSize(WARP1_OUTPUT_FRAME_SIZE); warp1->setMaxOutputFrameSize(std::get<0>(WARP1_OUTPUT_FRAME_SIZE) * std::get<1>(WARP1_OUTPUT_FRAME_SIZE) * 3); - warp1->setInterpolation(dai::node::Warp::Properties::Interpolation::BYPASS); + warp1->setInterpolation(dai::Interpolation::NEAREST_NEIGHBOR); warp1->setHwIds({1}); camRgb->preview.link(warp1->inputImage); @@ -47,7 +47,7 @@ int main() { // clang-format on warp2->setWarpMesh(mesh2, 3, 3); warp2->setMaxOutputFrameSize(maxFrameSize); - warp2->setInterpolation(dai::node::Warp::Properties::Interpolation::BICUBIC); + warp2->setInterpolation(dai::Interpolation::BICUBIC); warp2->setHwIds({2}); camRgb->preview.link(warp2->inputImage); diff --git a/include/depthai/pipeline/datatype/ImageManipConfig.hpp b/include/depthai/pipeline/datatype/ImageManipConfig.hpp index 521145316..b4b3be35e 100644 --- a/include/depthai/pipeline/datatype/ImageManipConfig.hpp +++ b/include/depthai/pipeline/datatype/ImageManipConfig.hpp @@ -29,7 +29,6 @@ class ImageManipConfig : public Buffer { using CropConfig = RawImageManipConfig::CropConfig; using ResizeConfig = RawImageManipConfig::ResizeConfig; using FormatConfig = RawImageManipConfig::FormatConfig; - using Interpolation = RawImageManipConfig::Interpolation; /// Construct ImageManipConfig message ImageManipConfig(); @@ -192,7 +191,7 @@ class ImageManipConfig : public Buffer { * Specify which interpolation method to use * @param interpolation type of interpolation */ - ImageManipConfig& setInterpolation(RawImageManipConfig::Interpolation interpolation); + ImageManipConfig& setInterpolation(dai::Interpolation interpolation); // Functions to retrieve properties /** @@ -251,7 +250,7 @@ class ImageManipConfig : public Buffer { Colormap getColormap() const; /// Retrieve which interpolation method to use - RawImageManipConfig::Interpolation getInterpolation() const; + dai::Interpolation getInterpolation() const; }; } // namespace dai diff --git a/include/depthai/pipeline/node/Warp.hpp b/include/depthai/pipeline/node/Warp.hpp index b86f608e3..836a69516 100644 --- a/include/depthai/pipeline/node/Warp.hpp +++ b/include/depthai/pipeline/node/Warp.hpp @@ -90,9 +90,9 @@ class Warp : public NodeCRTP { * Specify which interpolation method to use * @param interpolation type of interpolation */ - void setInterpolation(Properties::Interpolation interpolation); + void setInterpolation(dai::Interpolation interpolation); /// Retrieve which interpolation method to use - Properties::Interpolation getInterpolation() const; + dai::Interpolation getInterpolation() const; }; } // namespace node diff --git a/shared/depthai-shared b/shared/depthai-shared index 2d72c8b01..59f0a25d3 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 2d72c8b01898f28b53128541ceccdf6aafb940fb +Subproject commit 59f0a25d31d5c9d2fceeffff1ac4e23c934a20b3 diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index ca1f33bbc..13490dd6e 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -234,7 +234,7 @@ ImageManipConfig& ImageManipConfig::setKeepAspectRatio(bool keep) { return *this; } -ImageManipConfig& ImageManipConfig::setInterpolation(RawImageManipConfig::Interpolation interpolation) { +ImageManipConfig& ImageManipConfig::setInterpolation(dai::Interpolation interpolation) { cfg.interpolation = interpolation; return *this; } @@ -284,7 +284,7 @@ dai::Colormap ImageManipConfig::getColormap() const { return cfg.formatConfig.colormap; } -RawImageManipConfig::Interpolation ImageManipConfig::getInterpolation() const { +dai::Interpolation ImageManipConfig::getInterpolation() const { return cfg.interpolation; } diff --git a/src/pipeline/node/Warp.cpp b/src/pipeline/node/Warp.cpp index 43c7a4b86..d088e2947 100644 --- a/src/pipeline/node/Warp.cpp +++ b/src/pipeline/node/Warp.cpp @@ -86,11 +86,11 @@ std::vector Warp::getHwIds() const { return properties.warpHwIds; } -void Warp::setInterpolation(Warp::Properties::Interpolation interpolation) { +void Warp::setInterpolation(dai::Interpolation interpolation) { properties.interpolation = interpolation; } -Warp::Properties::Interpolation Warp::getInterpolation() const { +dai::Interpolation Warp::getInterpolation() const { return properties.interpolation; } From b2c65a88ebe862bcbccfe30f8fc90c8183750549 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 31 Mar 2023 21:30:34 +0300 Subject: [PATCH 03/63] Update FW with latest develop fixes --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 5b7fbd60d..d22c94ee3 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "2f3b8dfd45410502cfe35b54dca3d1f8aa95e188") +set(DEPTHAI_DEVICE_SIDE_COMMIT "dae73cd61d69834c89e5aa19d4af1176d34def11") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 15bb02f4165a25d7201d6182f34cbf0ff0ed9eee Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 31 Mar 2023 23:25:45 +0300 Subject: [PATCH 04/63] Update shared --- shared/depthai-shared | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/depthai-shared b/shared/depthai-shared index 59f0a25d3..4dd8446b5 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 59f0a25d31d5c9d2fceeffff1ac4e23c934a20b3 +Subproject commit 4dd8446b52a5ac9f5eab2d07da31236d4ad906dc From 73d36a3be7e2edd4c1a83ca9fce2089bdf65bb63 Mon Sep 17 00:00:00 2001 From: Andrej Susnik Date: Wed, 7 Jun 2023 18:40:47 +0200 Subject: [PATCH 05/63] Add example for read calibration in script node --- examples/Script/script_read_calibration.cpp | 31 +++++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 examples/Script/script_read_calibration.cpp diff --git a/examples/Script/script_read_calibration.cpp b/examples/Script/script_read_calibration.cpp new file mode 100644 index 000000000..64e5dc0c9 --- /dev/null +++ b/examples/Script/script_read_calibration.cpp @@ -0,0 +1,31 @@ +#include + +// Includes common necessary includes for development using depthai library +#include "depthai/depthai.hpp" + +int main() { + using namespace std; + + // Start defining a pipeline + dai::Pipeline pipeline; + + // Script node + auto script = pipeline.create(); + script->setScript(R"( + cal = Device.readCalibration2() + left_camera_id = cal.getStereoLeftCameraId() + right_camera_id = cal.getStereoRightCameraId() + + extrinsics = cal.getCameraExtrinsics(left_camera_id, right_camera_id) + intrinsics_left = cal.getCameraIntrinsics(left_camera_id) + + print(extrinsics) + print(intrinsics_left) + )"); + + // Connect to device with pipeline + dai::Device device(pipeline); + while(true) {} + + return 0; +} From c7e7c256956840be228957f4ef80105d6b35e576 Mon Sep 17 00:00:00 2001 From: Andrej Susnik Date: Wed, 7 Jun 2023 20:07:32 +0200 Subject: [PATCH 06/63] Add to cmake and fix errors --- examples/CMakeLists.txt | 1 + examples/Script/script_read_calibration.cpp | 14 +++++++++++++- 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 41272b289..e3b910291 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -320,6 +320,7 @@ dai_add_example(script_json_communication Script/script_json_communication.cpp O dai_add_example(script_change_pipeline_flow Script/script_change_pipeline_flow.cpp OFF) target_compile_definitions(script_change_pipeline_flow PRIVATE BLOB_PATH="${mobilenet_5shaves_blob}") dai_add_example(script_get_device_info Script/script_get_device_info.cpp ON) +dai_add_example(script_read_calibration Script/script_read_calibration.cpp ON) # SpatialDetection dai_add_example(spatial_location_calculator SpatialDetection/spatial_location_calculator.cpp ON) diff --git a/examples/Script/script_read_calibration.cpp b/examples/Script/script_read_calibration.cpp index 64e5dc0c9..19287f490 100644 --- a/examples/Script/script_read_calibration.cpp +++ b/examples/Script/script_read_calibration.cpp @@ -11,7 +11,10 @@ int main() { // Script node auto script = pipeline.create(); + script->setProcessor(dai::ProcessorType::LEON_CSS); script->setScript(R"( + import time + cal = Device.readCalibration2() left_camera_id = cal.getStereoLeftCameraId() right_camera_id = cal.getStereoRightCameraId() @@ -21,11 +24,20 @@ int main() { print(extrinsics) print(intrinsics_left) + + time.sleep(1) + node.io['end'].send(Buffer(32)) )"); + auto xout = pipeline.create(); + xout->setStreamName("end"); + + script->outputs["end"].link(xout->input); + // Connect to device with pipeline dai::Device device(pipeline); - while(true) {} + + device.getOutputQueue("end")->get(); return 0; } From 6884d77caa6778d2f46e7905bf03f41c4302594b Mon Sep 17 00:00:00 2001 From: Andrej Susnik Date: Tue, 20 Jun 2023 12:54:43 +0200 Subject: [PATCH 07/63] Change printf to node.info in script node read calibration example --- examples/Script/script_read_calibration.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Script/script_read_calibration.cpp b/examples/Script/script_read_calibration.cpp index 19287f490..9db5c5f25 100644 --- a/examples/Script/script_read_calibration.cpp +++ b/examples/Script/script_read_calibration.cpp @@ -22,8 +22,8 @@ int main() { extrinsics = cal.getCameraExtrinsics(left_camera_id, right_camera_id) intrinsics_left = cal.getCameraIntrinsics(left_camera_id) - print(extrinsics) - print(intrinsics_left) + node.info(extrinsics.__str__()) + node.info(intrinsics_left.__str__()) time.sleep(1) node.io['end'].send(Buffer(32)) From b0e37dcd6256d54560f91755bb06c8a6bacabf81 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 21 Jun 2023 21:11:38 +0300 Subject: [PATCH 08/63] ToF: Add median filter support --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/datatype/ToFConfig.hpp | 4 ++++ shared/depthai-shared | 2 +- src/pipeline/datatype/ToFConfig.cpp | 5 +++++ 4 files changed, 11 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 86f39611d..76c25efd0 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "f033fd9c7eb0b3578d12f90302e87759c78cfb36") +set(DEPTHAI_DEVICE_SIDE_COMMIT "f249378e290febb6402331a0b75ce1059e62a4e0") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/datatype/ToFConfig.hpp b/include/depthai/pipeline/datatype/ToFConfig.hpp index 39a8adf08..0d877ee99 100644 --- a/include/depthai/pipeline/datatype/ToFConfig.hpp +++ b/include/depthai/pipeline/datatype/ToFConfig.hpp @@ -30,6 +30,10 @@ class ToFConfig : public Buffer { ToFConfig& setFreqModUsed(dai::ToFConfig::DepthParams::TypeFMod fmod); ToFConfig& setAvgPhaseShuffle(bool enable); ToFConfig& setMinAmplitude(float minamp); + /** + * @param median Set kernel size for median filtering, or disable + */ + ToFConfig& setMedianFilter(MedianFilter median); /** * Set explicit configuration. diff --git a/shared/depthai-shared b/shared/depthai-shared index f03e9d9b0..ae671fbeb 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit f03e9d9b08df2c0a50b8a928901ce95b14f9c174 +Subproject commit ae671fbeb32b4f39d60fba8bda35b23305b8a961 diff --git a/src/pipeline/datatype/ToFConfig.cpp b/src/pipeline/datatype/ToFConfig.cpp index 4f8a625be..da1ce41ed 100644 --- a/src/pipeline/datatype/ToFConfig.cpp +++ b/src/pipeline/datatype/ToFConfig.cpp @@ -38,4 +38,9 @@ ToFConfig& ToFConfig::setMinAmplitude(float minamp) { return *this; } +ToFConfig& ToFConfig::setMedianFilter(MedianFilter median) { + cfg.depthParams.median = median; + return *this; +} + } // namespace dai From 23db0d6e5995d17bd2e4ba98582bb16198ef1bab Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 26 Jun 2023 22:12:31 +0300 Subject: [PATCH 09/63] Update FW to latest develop --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- examples/Script/script_read_calibration.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 76c25efd0..5ee1ffa2d 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "f249378e290febb6402331a0b75ce1059e62a4e0") +set(DEPTHAI_DEVICE_SIDE_COMMIT "1c4ac419c70d4baddb7afd78a3446e28286067bc") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/Script/script_read_calibration.cpp b/examples/Script/script_read_calibration.cpp index 9db5c5f25..f3aa277ab 100644 --- a/examples/Script/script_read_calibration.cpp +++ b/examples/Script/script_read_calibration.cpp @@ -31,7 +31,7 @@ int main() { auto xout = pipeline.create(); xout->setStreamName("end"); - + script->outputs["end"].link(xout->input); // Connect to device with pipeline From e52f10f2d9933f4e4a543bc02d70683147080f3a Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 4 Jul 2023 16:03:39 +0300 Subject: [PATCH 10/63] FW: Stereo: Apply alpha scaling parameter to RGB intrinsics when RGB alignment is enabled --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 5ee1ffa2d..60be1765f 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "1c4ac419c70d4baddb7afd78a3446e28286067bc") +set(DEPTHAI_DEVICE_SIDE_COMMIT "900949c33d6b683d78ad8084828b6ba9c2979d93") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 1702d31345357cdd9a856badd3d27dd76cc27dfc Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 4 Jul 2023 15:51:46 +0300 Subject: [PATCH 11/63] FW: fix CAM_D enumeration on OAK-FFC-4P R7 --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 60be1765f..6b415e3a2 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "900949c33d6b683d78ad8084828b6ba9c2979d93") +set(DEPTHAI_DEVICE_SIDE_COMMIT "6ff42a5c5a99cde04f015f6694d5e611f7dc2939") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 3ef1175944637c928ac571c9b1f5cff92161bfde Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 4 Jul 2023 19:38:49 +0300 Subject: [PATCH 12/63] Camera: move alpha parameter as optional to be consistent with stereo --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/node/Camera.hpp | 2 +- shared/depthai-shared | 2 +- src/pipeline/node/Camera.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 60be1765f..355a74557 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "900949c33d6b683d78ad8084828b6ba9c2979d93") +set(DEPTHAI_DEVICE_SIDE_COMMIT "91fd63cb4e50b716bbd22e667d86fcc904bee92c") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/node/Camera.hpp b/include/depthai/pipeline/node/Camera.hpp index bb44afa68..0e7f2c778 100644 --- a/include/depthai/pipeline/node/Camera.hpp +++ b/include/depthai/pipeline/node/Camera.hpp @@ -333,7 +333,7 @@ class Camera : public NodeCRTP { /// Set calibration alpha parameter that determines FOV of undistorted frames void setCalibrationAlpha(float alpha); /// Get calibration alpha parameter that determines FOV of undistorted frames - float getCalibrationAlpha() const; + tl::optional getCalibrationAlpha() const; /** * Configures whether the camera `raw` frames are saved as MIPI-packed to memory. diff --git a/shared/depthai-shared b/shared/depthai-shared index ae671fbeb..a6cf98371 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit ae671fbeb32b4f39d60fba8bda35b23305b8a961 +Subproject commit a6cf983712b273f02cc44bf777dc9df2193a2235 diff --git a/src/pipeline/node/Camera.cpp b/src/pipeline/node/Camera.cpp index 6edcc1150..66516d10e 100644 --- a/src/pipeline/node/Camera.cpp +++ b/src/pipeline/node/Camera.cpp @@ -271,7 +271,7 @@ void Camera::setCalibrationAlpha(float alpha) { properties.calibAlpha = alpha; } -float Camera::getCalibrationAlpha() const { +tl::optional Camera::getCalibrationAlpha() const { return properties.calibAlpha; } From 4faa36e1314958285b221430da4e2a639105b480 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 5 Jul 2023 14:40:38 +0300 Subject: [PATCH 13/63] Update FW --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 355a74557..1c3ba7130 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "91fd63cb4e50b716bbd22e667d86fcc904bee92c") +set(DEPTHAI_DEVICE_SIDE_COMMIT "78f6ce2dff2aa2edb9c8ea06106c46d268da8160") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From ca3de8621761d91489f43e92bd042a70237c6823 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 5 Jul 2023 20:24:33 +0300 Subject: [PATCH 14/63] BMI: Fix accumulating latency due to slow xlink read --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 1c3ba7130..015122689 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "78f6ce2dff2aa2edb9c8ea06106c46d268da8160") +set(DEPTHAI_DEVICE_SIDE_COMMIT "8a540fc8d3f116faaeddec8bb95864e6cb483786") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From cba779c7cfcfa6083cce301739fa90a1c0a2f485 Mon Sep 17 00:00:00 2001 From: Andrej Susnik Date: Wed, 12 Jul 2023 11:26:49 +0200 Subject: [PATCH 15/63] Fix constructors overriding maxUsbSpeed --- include/depthai/device/DeviceBase.hpp | 9 ++-- src/device/Device.cpp | 2 +- src/device/DeviceBase.cpp | 63 ++++++++++++++------------- tests/src/device_usbspeed_test.cpp | 35 +++++++++++++++ 4 files changed, 72 insertions(+), 37 deletions(-) diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 561c095bb..f93bb6675 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -292,8 +292,8 @@ class DeviceBase { /** * Connects to device 'devInfo' with custom config. - * @param devInfo DeviceInfo which specifies which device to connect to * @param config Device custom configuration to boot with + * @param devInfo DeviceInfo which specifies which device to connect to */ DeviceBase(Config config, const DeviceInfo& devInfo); @@ -364,8 +364,8 @@ class DeviceBase { /** * Connects to device specified by devInfo. - * @param version OpenVINO version which the device will be booted with - * @param config Config with which specifies which device to connect to + * @param config Config with which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to * @param maxUsbSpeed Maximum allowed USB speed */ DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); @@ -867,7 +867,6 @@ class DeviceBase { void init(OpenVINO::Version version); void init(OpenVINO::Version version, const dai::Path& pathToCmd); void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed); - void init(OpenVINO::Version version, bool usb2Mode, const dai::Path& pathToMvcmd); void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); void init(const Pipeline& pipeline); void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed); @@ -876,9 +875,7 @@ class DeviceBase { void init(const Pipeline& pipeline, const DeviceInfo& devInfo, bool usb2Mode); void init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); void init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd); - void init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& pathToMvcmd); void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); - void init(Config config, bool usb2Mode, const dai::Path& pathToMvcmd); void init(Config config, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); void init(Config config, UsbSpeed maxUsbSpeed); void init(Config config, const dai::Path& pathToCmd); diff --git a/src/device/Device.cpp b/src/device/Device.cpp index feabee10f..3cdf3948e 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -41,7 +41,7 @@ Device::Device(const Pipeline& pipeline, const dai::Path& pathToCmd) : DeviceBas tryStartPipeline(pipeline); } -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getDeviceConfig(), devInfo, false) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getDeviceConfig(), devInfo) { tryStartPipeline(pipeline); } diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 607568ac0..96076b747 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -333,7 +333,10 @@ DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, Usb } DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { - init(version, false, pathToCmd); + Config cfg; + cfg.version = version; + + init2(cfg, pathToCmd, {}); } DeviceBase::DeviceBase() : DeviceBase(OpenVINO::VERSION_UNIVERSAL) {} @@ -394,7 +397,7 @@ DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsb } DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } DeviceBase::DeviceBase(Config config, const dai::Path& pathToCmd) { @@ -407,12 +410,20 @@ DeviceBase::DeviceBase(Config config, UsbSpeed maxUsbSpeed) { void DeviceBase::init(OpenVINO::Version version) { tryGetDevice(); - init(version, false, ""); + + Config cfg; + cfg.version = version; + + init2(cfg, "", {}); } void DeviceBase::init(OpenVINO::Version version, const dai::Path& pathToCmd) { tryGetDevice(); - init(version, false, pathToCmd); + + Config cfg; + cfg.version = version; + + init2(cfg, pathToCmd, {}); } void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { @@ -422,7 +433,10 @@ void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { void DeviceBase::init(const Pipeline& pipeline) { tryGetDevice(); - init(pipeline, false, ""); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, "", pipeline); } void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { @@ -432,12 +446,18 @@ void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { void DeviceBase::init(const Pipeline& pipeline, const dai::Path& pathToCmd) { tryGetDevice(); - init(pipeline, false, pathToCmd); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, pathToCmd, pipeline); } void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo) { deviceInfo = devInfo; - init(pipeline, false, ""); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, "", pipeline); } void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { @@ -447,7 +467,10 @@ void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSp void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { deviceInfo = devInfo; - init(pipeline, false, pathToCmd); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, pathToCmd, pipeline); } void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) { @@ -457,7 +480,7 @@ void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) { void DeviceBase::init(Config config, const dai::Path& pathToCmd) { tryGetDevice(); - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { @@ -467,7 +490,7 @@ void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbS void DeviceBase::init(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { deviceInfo = devInfo; - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } DeviceBase::DeviceBase(Config config) { @@ -548,26 +571,6 @@ void DeviceBase::tryStartPipeline(const Pipeline& pipeline) { } } -void DeviceBase::init(OpenVINO::Version version, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg; - // Specify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - // Specify the OpenVINO version - cfg.version = version; - init2(cfg, pathToMvcmd, {}); -} -void DeviceBase::init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg = pipeline.getDeviceConfig(); - // Modify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - init2(cfg, pathToMvcmd, pipeline); -} -void DeviceBase::init(Config config, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg = config; - // Modify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - init2(cfg, pathToMvcmd, {}); -} void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) { Config cfg; // Specify usb speed diff --git a/tests/src/device_usbspeed_test.cpp b/tests/src/device_usbspeed_test.cpp index d5d99b7a5..21237a0aa 100644 --- a/tests/src/device_usbspeed_test.cpp +++ b/tests/src/device_usbspeed_test.cpp @@ -49,5 +49,40 @@ TEST_CASE("UsbSpeed::SUPER_PLUS") { dai::Pipeline p; makeInfo(p); dai::Device d(p, dai::UsbSpeed::SUPER_PLUS); + + verifyInfo(d); +} + +TEST_CASE("Pipeline config usb speed == SUPER") +{ + dai::Pipeline p; + makeInfo(p); + + dai::DeviceBase::Config cfg; + cfg.board.usb.maxSpeed = dai::UsbSpeed::SUPER; + + p.setBoardConfig(cfg.board); + + dai::Device d(p); + + CHECK(d.getUsbSpeed() == dai::UsbSpeed::SUPER); + + verifyInfo(d); +} + +TEST_CASE("Pipeline config usb speed == HIGH") +{ + dai::Pipeline p; + makeInfo(p); + + dai::DeviceBase::Config cfg; + cfg.board.usb.maxSpeed = dai::UsbSpeed::HIGH; + + p.setBoardConfig(cfg.board); + + dai::Device d(p); + + CHECK(d.getUsbSpeed() == dai::UsbSpeed::HIGH); + verifyInfo(d); } From 40df8f3aaa3b251b42a9d64f4c58a2a3d3294f6e Mon Sep 17 00:00:00 2001 From: Aniel Alexa Date: Fri, 14 Jul 2023 14:39:56 +0300 Subject: [PATCH 16/63] hasAutofocus fix based on device name/lensPosition --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 86f39611d..fc3c9c362 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "f033fd9c7eb0b3578d12f90302e87759c78cfb36") +set(DEPTHAI_DEVICE_SIDE_COMMIT "8d6106c43be8cf95d22ee85300a40dbd1b5617c6") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 147781eab95b0326a2e07daf32b3e0fbb706eb1c Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 27 Jul 2023 11:28:46 +0200 Subject: [PATCH 17/63] WIP: Device name improvements --- src/device/DeviceBase.cpp | 87 ++++++++++++++++++++++++++++++--------- 1 file changed, 68 insertions(+), 19 deletions(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 96076b747..379db28a6 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1062,31 +1062,80 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } +static std::vector split(const std::string& s, char delimiter) { + std::vector tokens; + size_t start = 0; + size_t end = s.find(delimiter); + + while (end != std::string::npos) { + tokens.push_back(s.substr(start, end - start)); + start = end + 1; + end = s.find(delimiter, start); + } + + tokens.push_back(s.substr(start, end)); + + return tokens; +} + std::string DeviceBase::getDeviceName() { std::string deviceName; - EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - eeprom = readCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - deviceName = eeprom.boardName; + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + std::string productNameOrFallback; + if((productNameOrFallback = eepromFactory.productName).empty()) { + if((productNameOrFallback = eeprom.productName).empty()) { + productNameOrFallback = eeprom.boardName; } } - - // Convert to device naming from display/product naming - // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); - std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); - std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); - - // Handle some known legacy cases - if(deviceName == "BW1098OBC") { - deviceName = "OAK-D"; - } else if(deviceName == "DM2097") { - deviceName = "OAK-D-CM4-POE"; - } else if(deviceName == "BW1097") { - deviceName = "OAK-D-CM3"; + bool hasDeviceName = true; + deviceName = productNameOrFallback; + if((deviceName = eepromFactory.deviceName).empty()) { + if((deviceName = eeprom.deviceName).empty()) { + deviceName = productNameOrFallback; + hasDeviceName = false; + } } - return deviceName; + if(hasDeviceName) { + return deviceName; + } else { + + // Convert to device naming from display/product naming + // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); + std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); + std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); + + // Handle some known legacy cases + if(deviceName == "BW1098OBC") { + deviceName = "OAK-D"; + } else if(deviceName == "DM2097") { + deviceName = "OAK-D-CM4-POE"; + } else if(deviceName == "BW1097") { + deviceName = "OAK-D-CM3"; + } + + std::vector skuDiff = { + "AF", "FF", "97", "OV9782" + }; + + // Regenerate from tokens + auto tokens = split(deviceName, '-'); + deviceName = ""; + for(int i = 0; i < tokens.size(); i++) { + const auto& token = tokens[i]; + + // check if token has to be removed + for(const auto& d : skuDiff) { + if(token == d) continue; + } + + if(i != 0) deviceName += "-"; + deviceName += token; + } + + return deviceName; + } } void DeviceBase::setLogOutputLevel(LogLevel level) { From dbed228593e201bc8c7d28ab24b967c32383cab6 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 27 Jul 2023 18:58:27 +0200 Subject: [PATCH 18/63] Added improvements to device naming --- CMakeLists.txt | 1 + include/depthai/device/CalibrationHandler.hpp | 31 +++++ include/depthai/device/DeviceBase.hpp | 8 +- shared/depthai-shared | 2 +- src/device/CalibrationHandler.cpp | 40 +++++- src/device/DeviceBase.cpp | 79 ++---------- src/utility/EepromDataParser.cpp | 88 ++++++++++++++ src/utility/EepromDataParser.hpp | 29 +++++ tests/CMakeLists.txt | 3 + tests/src/naming_test.cpp | 115 ++++++++++++++++++ 10 files changed, 322 insertions(+), 74 deletions(-) create mode 100644 src/utility/EepromDataParser.cpp create mode 100644 src/utility/EepromDataParser.hpp create mode 100644 tests/src/naming_test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index dc2972914..c2f27ae3e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -251,6 +251,7 @@ add_library(${TARGET_CORE_NAME} src/utility/Environment.cpp src/utility/XLinkGlobalProfilingLogger.cpp src/utility/Logging.cpp + src/utility/EepromDataParser.cpp src/xlink/XLinkConnection.cpp src/xlink/XLinkStream.cpp src/openvino/OpenVINO.cpp diff --git a/include/depthai/device/CalibrationHandler.hpp b/include/depthai/device/CalibrationHandler.hpp index 04ba756dd..8104707d6 100644 --- a/include/depthai/device/CalibrationHandler.hpp +++ b/include/depthai/device/CalibrationHandler.hpp @@ -353,6 +353,37 @@ class CalibrationHandler { uint32_t boardOptions, std::string boardCustom = ""); + /** + * Set the Board Info object. Creates version 7 EEPROM data + * + * @param deviceName Sets device name. + * @param productName Sets product name (alias). + * @param boardName Sets board name. + * @param boardRev Sets board revision id. + * @param boardConf Sets board configuration id. + * @param hardwareConf Sets hardware configuration id. + * @param batchName Sets batch name. + * @param batchTime Sets batch time (unix timestamp). + * @param boardCustom Sets a custom board (Default empty string). + */ + void setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom = ""); + + /** + * Set the deviceName which responses to getDeviceName of Device + * + * @param deviceName Sets device name. + */ + void setDeviceName(std::string productName); + /** * Set the productName which acts as alisas for users to identify the device * diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index f93bb6675..327f726fe 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -364,7 +364,7 @@ class DeviceBase { /** * Connects to device specified by devInfo. - * @param config Config with which the device will be booted with + * @param config Config with which the device will be booted with * @param devInfo DeviceInfo which specifies which device to connect to * @param maxUsbSpeed Maximum allowed USB speed */ @@ -456,6 +456,12 @@ class DeviceBase { */ std::string getDeviceName(); + /** + * Get product name if available + * @returns product name or empty string if not available + */ + std::string getProductName(); + /** * Get MxId of device * diff --git a/shared/depthai-shared b/shared/depthai-shared index 14c99ac36..24a4cd46c 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 14c99ac36195e88800cbee7fb55497dc762b12c6 +Subproject commit 24a4cd46c8e805a271b7d65c546efa3963ca0dc2 diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 15a4b6a29..c71d880c5 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -560,11 +560,49 @@ void CalibrationHandler::setBoardInfo(std::string productName, eepromData.boardRev = boardRev; eepromData.boardConf = boardConf; eepromData.hardwareConf = hardwareConf; - eepromData.batchName = batchName; eepromData.batchTime = batchTime; eepromData.boardCustom = boardCustom; eepromData.boardOptions = boardOptions; + if(batchName != "") { + logger::warn("batchTime parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom) { + eepromData.productName = productName; + eepromData.boardName = boardName; + eepromData.boardRev = boardRev; + eepromData.boardConf = boardConf; + eepromData.hardwareConf = hardwareConf; + eepromData.batchTime = batchTime; + eepromData.boardCustom = boardCustom; + eepromData.boardOptions = boardOptions; + eepromData.deviceName = deviceName; + + if(batchName != "") { + logger::warn("batchTime parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setDeviceName(std::string deviceName) { + eepromData.deviceName = deviceName; + // Bump version to V7 eepromData.version = 7; } diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 379db28a6..0fd6461c1 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -25,6 +25,7 @@ #include "utility/Initialization.hpp" #include "utility/PimplImpl.hpp" #include "utility/Resources.hpp" +#include "utility/EepromDataParser.hpp" // libraries #include "XLink/XLink.h" @@ -917,8 +918,8 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(w / rate); + r = static_cast(r / rate); lastData = data; @@ -1062,80 +1063,16 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } -static std::vector split(const std::string& s, char delimiter) { - std::vector tokens; - size_t start = 0; - size_t end = s.find(delimiter); - - while (end != std::string::npos) { - tokens.push_back(s.substr(start, end - start)); - start = end + 1; - end = s.find(delimiter, start); - } - - tokens.push_back(s.substr(start, end)); - - return tokens; +std::string DeviceBase::getProductName() { + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + return utility::parseProductName(eeprom, eepromFactory); } std::string DeviceBase::getDeviceName() { - std::string deviceName; EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); EepromData eeprom = readCalibrationOrDefault().getEepromData(); - std::string productNameOrFallback; - if((productNameOrFallback = eepromFactory.productName).empty()) { - if((productNameOrFallback = eeprom.productName).empty()) { - productNameOrFallback = eeprom.boardName; - } - } - bool hasDeviceName = true; - deviceName = productNameOrFallback; - if((deviceName = eepromFactory.deviceName).empty()) { - if((deviceName = eeprom.deviceName).empty()) { - deviceName = productNameOrFallback; - hasDeviceName = false; - } - } - - if(hasDeviceName) { - return deviceName; - } else { - - // Convert to device naming from display/product naming - // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); - std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); - std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); - - // Handle some known legacy cases - if(deviceName == "BW1098OBC") { - deviceName = "OAK-D"; - } else if(deviceName == "DM2097") { - deviceName = "OAK-D-CM4-POE"; - } else if(deviceName == "BW1097") { - deviceName = "OAK-D-CM3"; - } - - std::vector skuDiff = { - "AF", "FF", "97", "OV9782" - }; - - // Regenerate from tokens - auto tokens = split(deviceName, '-'); - deviceName = ""; - for(int i = 0; i < tokens.size(); i++) { - const auto& token = tokens[i]; - - // check if token has to be removed - for(const auto& d : skuDiff) { - if(token == d) continue; - } - - if(i != 0) deviceName += "-"; - deviceName += token; - } - - return deviceName; - } + return utility::parseDeviceName(eeprom, eepromFactory); } void DeviceBase::setLogOutputLevel(LogLevel level) { diff --git a/src/utility/EepromDataParser.cpp b/src/utility/EepromDataParser.cpp new file mode 100644 index 000000000..502a7329c --- /dev/null +++ b/src/utility/EepromDataParser.cpp @@ -0,0 +1,88 @@ +#include "utility/EepromDataParser.hpp" + +namespace dai +{ +namespace utility +{ + +std::vector split(const std::string& s, char delimiter) { + std::vector tokens; + size_t start = 0; + size_t end = s.find(delimiter); + + while (end != std::string::npos) { + tokens.push_back(s.substr(start, end - start)); + start = end + 1; + end = s.find(delimiter, start); + } + + tokens.push_back(s.substr(start, end)); + + return tokens; +} + +std::string parseProductName(EepromData eeprom, EepromData eepromFactory) { + std::string productName; + if((productName = eepromFactory.productName).empty()) { + if((productName = eeprom.productName).empty()) { + productName = eeprom.boardName; + } + } + + // Convert to device naming from display/product naming + std::transform(productName.begin(), productName.end(), productName.begin(), [](int c) { return std::toupper(c); }); + std::replace(productName.begin(), productName.end(), ' ', '-'); + + // Handle some known legacy cases + if(productName == "BW1098OBC") { + productName = "OAK-D"; + } else if(productName == "DM2097") { + productName = "OAK-D-CM4-POE"; + } else if(productName == "BW1097") { + productName = "OAK-D-CM3"; + } + + return productName; +} + + +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory) { + std::string deviceName; + if((deviceName = eepromFactory.deviceName).empty()) { + if((deviceName = eeprom.deviceName).empty()) { + // Constant skuDiff array + const std::array skuDiff = {"AF", "FF", "97", "9782", "OV9782"}; + + // Parse productName and use that to generate device name + deviceName = parseProductName(eeprom, eepromFactory); + + // Regenerate from tokens + auto tokens = split(deviceName, '-'); + deviceName = ""; + for(int i = 0; i < tokens.size(); i++) { + const auto& token = tokens[i]; + + // check if token has to be removed + bool skipToken = false; + for(const auto& d : skuDiff) { + if(token == d) { + skipToken = true; + break; + } + } + if(skipToken) continue; + + if(i != 0) deviceName += "-"; + deviceName += token; + } + + // Return generated deviceName + return deviceName; + } + } + + return deviceName; +} + +} // namespace utility +} // namespace dai diff --git a/src/utility/EepromDataParser.hpp b/src/utility/EepromDataParser.hpp new file mode 100644 index 000000000..0bab9f574 --- /dev/null +++ b/src/utility/EepromDataParser.hpp @@ -0,0 +1,29 @@ +#pragma once + +#include "depthai-shared/common/EepromData.hpp" + +namespace dai +{ +namespace utility +{ + +/// @brief Splits given string by delimiter +/// @param s string to split +/// @param delimiter character by which to split +/// @return vector of split strings +std::vector split(const std::string& s, char delimiter); + +/// @brief Parses product name from given EepromData combination +/// @param eeprom EepromData containing fields to parse product name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning product name or empty +std::string parseProductName(EepromData eeprom, EepromData eepromFactory = {}); + +/// @brief Parses device name from given EepromData combination +/// @param eeprom EepromData containing fields to parse device name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning device name or empty +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory = {}); + +} // namespace utility +} // namespace dai diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 21260e2f8..01a037d35 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -216,6 +216,9 @@ dai_test_compile_definitions(openvino_blob_test PRIVATE # Bootloader configuration tests dai_add_test(bootloader_config_test src/bootloader_config_test.cpp) +# Eeprom naming parsing tests +dai_add_test(naming_test src/naming_test.cpp) + # Device USB Speed and serialization macros test dai_add_test(device_usbspeed_test src/device_usbspeed_test.cpp CONFORMING) dai_add_test(device_usbspeed_test_17 src/device_usbspeed_test.cpp CONFORMING CXX_STANDARD 17) diff --git a/tests/src/naming_test.cpp b/tests/src/naming_test.cpp new file mode 100644 index 000000000..78a49eca2 --- /dev/null +++ b/tests/src/naming_test.cpp @@ -0,0 +1,115 @@ +#include + +#include "../../src/utility/EepromDataParser.hpp" + +struct ProductDevice { + std::string oldProductName, productName, deviceName; +}; +std::vector productToDeviceNames = { + {"OAK-D LR", "OAK-D-LR", "OAK-D-LR"}, + {"OAK-D", "OAK-D", "OAK-D"}, + {"OAK-FFC 1P PoE", "OAK-FFC-1P-POE", "OAK-FFC-1P-POE"}, + {"OAK-FFC 4P", "OAK-FFC-4P", "OAK-FFC-4P"}, + {"OAK-FFC 3P", "OAK-FFC-3P", "OAK-FFC-3P"}, + {"OAK-D CM4", "OAK-D-CM4", "OAK-D-CM4"}, + {"OAK-D SR", "OAK-D-SR", "OAK-D-SR"}, + {"OAK-D PoE AF", "OAK-D-POE-AF", "OAK-D-POE"}, + {"OAK-D CM4 PoE", "OAK-D-CM4-POE", "OAK-D-CM4-POE"}, + {"rae", "RAE", "RAE"}, + {"OAK-FFC 6P", "OAK-FFC-6P", "OAK-FFC-6P"}, + {"OAK-D Lite", "OAK-D-LITE", "OAK-D-LITE"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D Pro AF", "OAK-D-PRO-AF", "OAK-D-PRO"}, + {"OAK-D Pro FF 97", "OAK-D-PRO-FF-97", "OAK-D-PRO"}, + {"OAK-D Pro FF", "OAK-D-PRO-FF", "OAK-D-PRO"}, + {"OAK-D Pro W 97", "OAK-D-PRO-W-97", "OAK-D-PRO-W"}, + {"OAK-D Pro W OV9782", "OAK-D-PRO-W-OV9782", "OAK-D-PRO-W"}, + {"OAK-D Pro W", "OAK-D-PRO-W", "OAK-D-PRO-W"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D W 97", "OAK-D-W-97", "OAK-D-W"}, + {"OAK-D SR PoE", "OAK-D-SR-POE", "OAK-D-SR-POE"}, + {"OAK-FFC-4P PoE", "OAK-FFC-4P-POE", "OAK-FFC-4P-POE"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1-FF 97", "OAK-1-FF-97", "OAK-1"}, + {"OAK-1 FF", "OAK-1-FF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W 97", "OAK-1-W-97", "OAK-1-W"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D S2 PoE AF", "OAK-D-S2-POE-AF", "OAK-D-S2-POE"}, + {"OAK-D S2 PoE FF", "OAK-D-S2-POE-FF", "OAK-D-S2-POE"}, + {"OAK-D W PoE", "OAK-D-W-POE", "OAK-D-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro W PoE 97", "OAK-D-PRO-W-POE-97", "OAK-D-PRO-W-POE"}, + {"OAK-D W PoE 97", "OAK-D-W-POE-97", "OAK-D-W-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + + // Special cases, resolved by modifying eeprom instead + // {"OAK-D PoE C22", "OAK-D-POE-C22", "OAK-D-POE"}, + // {"", "OAK-D-CM4-POE-C11", "OAK-D-CM4-POE"}, + // {"", "OAK-D-CM4-POE-C24", "OAK-D-CM4-POE"}, + //{"OAK-D Pro AF PB", "OAK-D-PRO-AF-PB", "OAK-D-PRO"}, + // {"OAK-D Pro FF C13", "OAK-D-PRO-FF-C13", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-C17", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#1", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#2", "OAK-D-PRO"}, + // {"OAK-D Pro W C06", "OAK-D-PRO-W-C06", "OAK-D-PRO-W"}, + // {"OAK-D Pro FF", "OAK-D-PRO-W-C16", "OAK-D-PRO-W"}, + // {"", "OAK-D-W-C15", "OAK-D-W"}, + // {"", "OAK-D-PRO-W-DEV", "OAK-D-PRO-W-DEV"}, + // {"", "OAK-1-LITE-C05", "OAK-1-LITE"}, + // {"OAK-1 AF", "OAK-1-AF-C20", "OAK-1"}, + // {"OAK-D Pro PoE AF C18", "OAK-D-PRO-POE-AF-C18", "OAK-D-PRO-POE-C18"}, + // {"OAK-D Pro W PoE C01", "OAK-D-PRO-W-POE-C01", "OAK-D-PRO-W-POE-C01"}, + +}; + +TEST_CASE("parsing") { + + for (size_t i = 0; i < productToDeviceNames.size(); i++) { + INFO("Testing with iteration number: " << i); + + const auto& pd = productToDeviceNames[i]; + dai::EepromData data; + data.productName = pd.productName; + + // Test parsing of device name + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + data.productName = pd.oldProductName; + REQUIRE(pd.productName == dai::utility::parseProductName(data)); + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + + // Test parsing directly to device name + data.deviceName = pd.deviceName; + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + } + +} \ No newline at end of file From 0e37dcde91afc4c633da40eb47887ec266314733 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 31 Jul 2023 14:37:42 +0200 Subject: [PATCH 19/63] Fixed device related logging --- src/device/DeviceBase.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 96076b747..a2bb2ddcb 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -602,6 +602,12 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Device - BoardConfig: {} \nlibnop:{}", jBoardConfig.dump(), spdlog::to_hex(utility::serialize(config.board))); } @@ -738,7 +744,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional lock(pimpl->rpcMutex); // Log the request data - if(logger::get_level() == spdlog::level::trace) { + if(getLogOutputLevel() == LogLevel::TRACE) { pimpl->logger.trace("RPC: {}", nlohmann::json::from_msgpack(request).dump()); } @@ -821,7 +827,6 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Schema dump: {}", jSchema.dump()); nlohmann::json jAssets = assets; From e8441f007433e361ca708558a599a2036dd0c73f Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 11 Aug 2023 13:13:45 +0200 Subject: [PATCH 20/63] Moved ts, tsDevice, and sequenceNum from descendants to RawBuffer --- src/pipeline/datatype/StreamMessageParser.cpp | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/src/pipeline/datatype/StreamMessageParser.cpp b/src/pipeline/datatype/StreamMessageParser.cpp index a000b205d..c6cb2eddb 100644 --- a/src/pipeline/datatype/StreamMessageParser.cpp +++ b/src/pipeline/datatype/StreamMessageParser.cpp @@ -114,13 +114,9 @@ std::shared_ptr StreamMessageParser::parseMessage(streamPacketDesc_t* // Create corresponding object switch(objectType) { - // RawBuffer is special case, no metadata is actually serialized - case DatatypeEnum::Buffer: { - // RawBuffer is special case, no metadata is actually serialized - auto pBuf = std::make_shared(); - pBuf->data = std::move(data); - return pBuf; - } break; + case DatatypeEnum::Buffer: + return parseDatatype(metadataStart, serializedObjectSize, data); + break; case DatatypeEnum::ImgFrame: return parseDatatype(metadataStart, serializedObjectSize, data); From bebb3d04a4f446e772d44d14d6fd286c726b7564 Mon Sep 17 00:00:00 2001 From: asahtik Date: Mon, 14 Aug 2023 16:04:05 +0200 Subject: [PATCH 21/63] Added getters and setters --- include/depthai/pipeline/datatype/Buffer.hpp | 32 +++++++++++++++++ src/pipeline/datatype/Buffer.cpp | 35 +++++++++++++++++++ src/pipeline/datatype/StreamMessageParser.cpp | 5 +-- 3 files changed, 68 insertions(+), 4 deletions(-) diff --git a/include/depthai/pipeline/datatype/Buffer.hpp b/include/depthai/pipeline/datatype/Buffer.hpp index 921041827..57198590b 100644 --- a/include/depthai/pipeline/datatype/Buffer.hpp +++ b/include/depthai/pipeline/datatype/Buffer.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -34,6 +35,37 @@ class Buffer : public ADatatype { * @param data Moves data to internal buffer */ void setData(std::vector&& data); + + /** + * Retrieves timestamp related to dai::Clock::now() + */ + std::chrono::time_point getTimestamp() const; + + /** + * Retrieves timestamp directly captured from device's monotonic clock, + * not synchronized to host time. Used mostly for debugging + */ + std::chrono::time_point getTimestampDevice() const; + + /** + * Retrieves sequence number + */ + int64_t getSequenceNum() const; + + /** + * Sets timestamp related to dai::Clock::now() + */ + Buffer& setTimestamp(std::chrono::time_point timestamp); + + /** + * Sets timestamp related to dai::Clock::now() + */ + Buffer& setTimestampDevice(std::chrono::time_point timestamp); + + /** + * Retrieves sequence number + */ + Buffer& setSequenceNum(int64_t sequenceNum); }; } // namespace dai diff --git a/src/pipeline/datatype/Buffer.cpp b/src/pipeline/datatype/Buffer.cpp index fca09ebce..824359c87 100644 --- a/src/pipeline/datatype/Buffer.cpp +++ b/src/pipeline/datatype/Buffer.cpp @@ -22,4 +22,39 @@ void Buffer::setData(std::vector&& data) { raw->data = std::move(data); } +// getters +std::chrono::time_point Buffer::getTimestamp() const { + using namespace std::chrono; + return time_point{seconds(raw->ts.sec) + nanoseconds(raw->ts.nsec)}; +} +std::chrono::time_point Buffer::getTimestampDevice() const { + using namespace std::chrono; + return time_point{seconds(raw->tsDevice.sec) + nanoseconds(raw->tsDevice.nsec)}; +} +int64_t Buffer::getSequenceNum() const { + return raw->sequenceNum; +} + +// setters +Buffer& Buffer::setTimestamp(std::chrono::time_point tp) { + // Set timestamp from timepoint + using namespace std::chrono; + auto ts = tp.time_since_epoch(); + raw->ts.sec = duration_cast(ts).count(); + raw->ts.nsec = duration_cast(ts).count() % 1000000000; + return *this; +} +Buffer& Buffer::setTimestampDevice(std::chrono::time_point tp) { + // Set timestamp from timepoint + using namespace std::chrono; + auto ts = tp.time_since_epoch(); + raw->tsDevice.sec = duration_cast(ts).count(); + raw->ts.nsec = duration_cast(ts).count() % 1000000000; + return *this; +} +Buffer& Buffer::setSequenceNum(int64_t sequenceNum) { + raw->sequenceNum = sequenceNum; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/StreamMessageParser.cpp b/src/pipeline/datatype/StreamMessageParser.cpp index c6cb2eddb..db52b55d4 100644 --- a/src/pipeline/datatype/StreamMessageParser.cpp +++ b/src/pipeline/datatype/StreamMessageParser.cpp @@ -206,10 +206,7 @@ std::shared_ptr StreamMessageParser::parseMessageToADatatype(streamPa switch(objectType) { case DatatypeEnum::Buffer: { - // RawBuffer is special case, no metadata is actually serialized - auto pBuf = std::make_shared(); - pBuf->data = std::move(data); - return std::make_shared(pBuf); + return std::make_shared(parseDatatype(metadataStart, serializedObjectSize, data)); } break; case DatatypeEnum::ImgFrame: From a175a263f35f1203c8c8f7cc51cab07a2311c1c1 Mon Sep 17 00:00:00 2001 From: Aniel Alexa Date: Mon, 14 Aug 2023 17:00:18 +0300 Subject: [PATCH 22/63] z_map for tof --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index b4b6bdf21..bbaddb7ec 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,8 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" - -set(DEPTHAI_DEVICE_SIDE_COMMIT "8d6106c43be8cf95d22ee85300a40dbd1b5617c6") +set(DEPTHAI_DEVICE_SIDE_COMMIT "1d4e70a72c7eb43692fa4dfac200436573089741") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 2a25f0f9475a9ec50f959e383b1d4f196a6e6da6 Mon Sep 17 00:00:00 2001 From: asahtik Date: Tue, 15 Aug 2023 16:29:33 +0200 Subject: [PATCH 23/63] ts to tsDevice fix --- src/pipeline/datatype/Buffer.cpp | 2 +- src/pipeline/datatype/NNData.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/pipeline/datatype/Buffer.cpp b/src/pipeline/datatype/Buffer.cpp index 824359c87..a0251d7bf 100644 --- a/src/pipeline/datatype/Buffer.cpp +++ b/src/pipeline/datatype/Buffer.cpp @@ -49,7 +49,7 @@ Buffer& Buffer::setTimestampDevice(std::chrono::time_pointtsDevice.sec = duration_cast(ts).count(); - raw->ts.nsec = duration_cast(ts).count() % 1000000000; + raw->tsDevice.nsec = duration_cast(ts).count() % 1000000000; return *this; } Buffer& Buffer::setSequenceNum(int64_t sequenceNum) { diff --git a/src/pipeline/datatype/NNData.cpp b/src/pipeline/datatype/NNData.cpp index aa35ce9eb..16abf9af8 100644 --- a/src/pipeline/datatype/NNData.cpp +++ b/src/pipeline/datatype/NNData.cpp @@ -296,7 +296,7 @@ NNData& NNData::setTimestampDevice(std::chrono::time_point(ts).count(); - rawNn.ts.nsec = duration_cast(ts).count() % 1000000000; + rawNn.tsDevice.nsec = duration_cast(ts).count() % 1000000000; return *this; } NNData& NNData::setSequenceNum(int64_t sequenceNum) { From 977cefb5dca8d583b334b75b02d366fa17088f46 Mon Sep 17 00:00:00 2001 From: Erol444 Date: Mon, 17 Apr 2023 11:37:17 +0200 Subject: [PATCH 24/63] Updated ColorCamera's setSensorCrop comment for documentation --- include/depthai/pipeline/node/ColorCamera.hpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index dc2e1b2e2..0f2890e71 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -286,7 +286,9 @@ class ColorCamera : public NodeCRTP { void sensorCenterCrop(); /** - * Specifies sensor crop rectangle + * Specifies the cropping that happens when converting ISP to video output. By default, video will be center cropped + * from the ISP output. Note that this doesn't actually do on-sensor cropping (and MIPI-stream only that region), but + * it does postprocessing on the ISP (on RVC). * @param x Top left X coordinate * @param y Top left Y coordinate */ From 6302eebb2f321e1528ba7d806d8e7ccf05f85df0 Mon Sep 17 00:00:00 2001 From: asahtik Date: Thu, 17 Aug 2023 14:25:30 +0200 Subject: [PATCH 25/63] Removed redundant getters and setters --- .../depthai/pipeline/datatype/AprilTags.hpp | 16 ----------- .../pipeline/datatype/ImgDetections.hpp | 16 ----------- .../depthai/pipeline/datatype/ImgFrame.hpp | 19 ++----------- include/depthai/pipeline/datatype/NNData.hpp | 16 ----------- .../datatype/SpatialImgDetections.hpp | 16 ----------- .../SpatialLocationCalculatorData.hpp | 16 ----------- .../pipeline/datatype/TrackedFeatures.hpp | 16 ----------- .../depthai/pipeline/datatype/Tracklets.hpp | 16 ----------- src/pipeline/datatype/AprilTags.cpp | 28 ++----------------- src/pipeline/datatype/ImgDetections.cpp | 28 ++----------------- src/pipeline/datatype/ImgFrame.cpp | 28 +++---------------- src/pipeline/datatype/NNData.cpp | 28 ++----------------- .../datatype/SpatialImgDetections.cpp | 28 ++----------------- .../SpatialLocationCalculatorData.cpp | 28 ++----------------- src/pipeline/datatype/TrackedFeatures.cpp | 28 ++----------------- src/pipeline/datatype/Tracklets.cpp | 28 ++----------------- 16 files changed, 27 insertions(+), 328 deletions(-) diff --git a/include/depthai/pipeline/datatype/AprilTags.hpp b/include/depthai/pipeline/datatype/AprilTags.hpp index f644302ca..f11d31f40 100644 --- a/include/depthai/pipeline/datatype/AprilTags.hpp +++ b/include/depthai/pipeline/datatype/AprilTags.hpp @@ -25,22 +25,6 @@ class AprilTags : public Buffer { std::vector& aprilTags; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/ImgDetections.hpp b/include/depthai/pipeline/datatype/ImgDetections.hpp index 9a26304a5..53ba49fe3 100644 --- a/include/depthai/pipeline/datatype/ImgDetections.hpp +++ b/include/depthai/pipeline/datatype/ImgDetections.hpp @@ -38,22 +38,6 @@ class ImgDetections : public Buffer { * Retrieves image sequence number */ ImgDetections& setSequenceNum(int64_t sequenceNum); - - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ImgFrame.hpp b/include/depthai/pipeline/datatype/ImgFrame.hpp index 1545bc4b7..f41ef5c4b 100644 --- a/include/depthai/pipeline/datatype/ImgFrame.hpp +++ b/include/depthai/pipeline/datatype/ImgFrame.hpp @@ -31,6 +31,8 @@ class ImgFrame : public Buffer { using Type = RawImgFrame::Type; using Specs = RawImgFrame::Specs; using CameraSettings = RawImgFrame::CameraSettings; + using Buffer::getTimestamp; + using Buffer::getTimestampDevice; /** * Construct ImgFrame message. @@ -40,18 +42,6 @@ class ImgFrame : public Buffer { explicit ImgFrame(std::shared_ptr ptr); virtual ~ImgFrame() = default; - // getters - /** - * Retrieves image timestamp (end of exposure) related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp (end of exposure) directly captured from device's monotonic clock, - * not synchronized to host time. Used when monotonicity is required. - */ - std::chrono::time_point getTimestampDevice() const; - // getters /** * Retrieves image timestamp (at the specified offset of exposure) related to dai::Clock::now() @@ -74,11 +64,6 @@ class ImgFrame : public Buffer { */ unsigned int getCategory() const; - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Retrieves image width in pixels */ diff --git a/include/depthai/pipeline/datatype/NNData.hpp b/include/depthai/pipeline/datatype/NNData.hpp index 980b32102..814f4c948 100644 --- a/include/depthai/pipeline/datatype/NNData.hpp +++ b/include/depthai/pipeline/datatype/NNData.hpp @@ -140,22 +140,6 @@ class NNData : public Buffer { */ std::vector getFirstLayerInt32() const; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/SpatialImgDetections.hpp b/include/depthai/pipeline/datatype/SpatialImgDetections.hpp index 0e0a76f5d..30876a462 100644 --- a/include/depthai/pipeline/datatype/SpatialImgDetections.hpp +++ b/include/depthai/pipeline/datatype/SpatialImgDetections.hpp @@ -43,22 +43,6 @@ class SpatialImgDetections : public Buffer { * Retrieves image sequence number */ SpatialImgDetections& setSequenceNum(int64_t sequenceNum); - - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp b/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp index 9f2cda338..c6a5586a9 100644 --- a/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp +++ b/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp @@ -31,22 +31,6 @@ class SpatialLocationCalculatorData : public Buffer { std::vector& spatialLocations; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/TrackedFeatures.hpp b/include/depthai/pipeline/datatype/TrackedFeatures.hpp index 158c83b03..45817658e 100644 --- a/include/depthai/pipeline/datatype/TrackedFeatures.hpp +++ b/include/depthai/pipeline/datatype/TrackedFeatures.hpp @@ -25,22 +25,6 @@ class TrackedFeatures : public Buffer { std::vector& trackedFeatures; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/Tracklets.hpp b/include/depthai/pipeline/datatype/Tracklets.hpp index f5ba6543d..278818d4b 100644 --- a/include/depthai/pipeline/datatype/Tracklets.hpp +++ b/include/depthai/pipeline/datatype/Tracklets.hpp @@ -30,22 +30,6 @@ class Tracklets : public Buffer { */ std::vector& tracklets; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/src/pipeline/datatype/AprilTags.cpp b/src/pipeline/datatype/AprilTags.cpp index 38fba14c9..fa81e5bb5 100644 --- a/src/pipeline/datatype/AprilTags.cpp +++ b/src/pipeline/datatype/AprilTags.cpp @@ -10,39 +10,17 @@ AprilTags::AprilTags() : Buffer(std::make_shared()), rawdata(*dyna AprilTags::AprilTags(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), aprilTags(rawdata.aprilTags) {} -// getters -std::chrono::time_point AprilTags::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point AprilTags::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t AprilTags::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters AprilTags& AprilTags::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } AprilTags& AprilTags::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } AprilTags& AprilTags::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai \ No newline at end of file diff --git a/src/pipeline/datatype/ImgDetections.cpp b/src/pipeline/datatype/ImgDetections.cpp index c0d9ad85c..b9eb5f75d 100644 --- a/src/pipeline/datatype/ImgDetections.cpp +++ b/src/pipeline/datatype/ImgDetections.cpp @@ -13,36 +13,14 @@ ImgDetections::ImgDetections(std::shared_ptr ptr) // setters ImgDetections& ImgDetections::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.ts.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } ImgDetections& ImgDetections::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.tsDevice.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } ImgDetections& ImgDetections::setSequenceNum(int64_t sequenceNum) { - dets.sequenceNum = sequenceNum; - return *this; -} - -// getters -std::chrono::time_point ImgDetections::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(dets.ts.sec) + nanoseconds(dets.ts.nsec)}; -} -std::chrono::time_point ImgDetections::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(dets.tsDevice.sec) + nanoseconds(dets.tsDevice.nsec)}; -} -int64_t ImgDetections::getSequenceNum() const { - return dets.sequenceNum; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/ImgFrame.cpp b/src/pipeline/datatype/ImgFrame.cpp index d7f98d8a9..fda7a4899 100644 --- a/src/pipeline/datatype/ImgFrame.cpp +++ b/src/pipeline/datatype/ImgFrame.cpp @@ -17,14 +17,6 @@ ImgFrame::ImgFrame(std::shared_ptr ptr) : Buffer(std::move(ptr)), i // helpers // getters -std::chrono::time_point ImgFrame::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(img.ts.sec) + nanoseconds(img.ts.nsec)}; -} -std::chrono::time_point ImgFrame::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(img.tsDevice.sec) + nanoseconds(img.tsDevice.nsec)}; -} std::chrono::time_point ImgFrame::getTimestamp(CameraExposureOffset offset) const { auto ts = getTimestamp(); auto expTime = getExposureTime(); @@ -39,7 +31,7 @@ std::chrono::time_point ImgFrame::getTimestampDevice(CameraExposureOffset offset) const { - auto ts = getTimestampDevice(); + auto ts = getTimestamp(); auto expTime = getExposureTime(); switch(offset) { case CameraExposureOffset::START: @@ -58,9 +50,6 @@ unsigned int ImgFrame::getInstanceNum() const { unsigned int ImgFrame::getCategory() const { return img.category; } -int64_t ImgFrame::getSequenceNum() const { - return img.sequenceNum; -} unsigned int ImgFrame::getWidth() const { return img.fb.width; } @@ -86,19 +75,11 @@ int ImgFrame::getLensPosition() const { // setters ImgFrame& ImgFrame::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - img.ts.sec = duration_cast(ts).count(); - img.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } ImgFrame& ImgFrame::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - img.tsDevice.sec = duration_cast(ts).count(); - img.tsDevice.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } ImgFrame& ImgFrame::setInstanceNum(unsigned int instanceNum) { img.instanceNum = instanceNum; @@ -109,8 +90,7 @@ ImgFrame& ImgFrame::setCategory(unsigned int category) { return *this; } ImgFrame& ImgFrame::setSequenceNum(int64_t sequenceNum) { - img.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } ImgFrame& ImgFrame::setWidth(unsigned int width) { img.fb.width = width; diff --git a/src/pipeline/datatype/NNData.cpp b/src/pipeline/datatype/NNData.cpp index 16abf9af8..ab765e63b 100644 --- a/src/pipeline/datatype/NNData.cpp +++ b/src/pipeline/datatype/NNData.cpp @@ -269,39 +269,17 @@ std::vector NNData::getFirstLayerInt32() const { return {}; } -// getters -std::chrono::time_point NNData::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawNn.ts.sec) + nanoseconds(rawNn.ts.nsec)}; -} -std::chrono::time_point NNData::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawNn.tsDevice.sec) + nanoseconds(rawNn.tsDevice.nsec)}; -} -int64_t NNData::getSequenceNum() const { - return rawNn.sequenceNum; -} - // setters NNData& NNData::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawNn.ts.sec = duration_cast(ts).count(); - rawNn.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } NNData& NNData::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawNn.tsDevice.sec = duration_cast(ts).count(); - rawNn.tsDevice.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } NNData& NNData::setSequenceNum(int64_t sequenceNum) { - rawNn.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/SpatialImgDetections.cpp b/src/pipeline/datatype/SpatialImgDetections.cpp index 76210ddea..89ee58e8d 100644 --- a/src/pipeline/datatype/SpatialImgDetections.cpp +++ b/src/pipeline/datatype/SpatialImgDetections.cpp @@ -14,36 +14,14 @@ SpatialImgDetections::SpatialImgDetections(std::shared_ptr tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.ts.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } SpatialImgDetections& SpatialImgDetections::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.tsDevice.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } SpatialImgDetections& SpatialImgDetections::setSequenceNum(int64_t sequenceNum) { - dets.sequenceNum = sequenceNum; - return *this; -} - -// getters -std::chrono::time_point SpatialImgDetections::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(dets.ts.sec) + nanoseconds(dets.ts.nsec)}; -} -std::chrono::time_point SpatialImgDetections::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(dets.tsDevice.sec) + nanoseconds(dets.tsDevice.nsec)}; -} -int64_t SpatialImgDetections::getSequenceNum() const { - return dets.sequenceNum; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/SpatialLocationCalculatorData.cpp b/src/pipeline/datatype/SpatialLocationCalculatorData.cpp index 16e99abc5..c6edf0e3d 100644 --- a/src/pipeline/datatype/SpatialLocationCalculatorData.cpp +++ b/src/pipeline/datatype/SpatialLocationCalculatorData.cpp @@ -15,41 +15,19 @@ std::vector& SpatialLocationCalculatorData::getSpatialLocation return rawdata.spatialLocations; } -// getters -std::chrono::time_point SpatialLocationCalculatorData::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point SpatialLocationCalculatorData::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t SpatialLocationCalculatorData::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters SpatialLocationCalculatorData& SpatialLocationCalculatorData::setTimestamp( std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } SpatialLocationCalculatorData& SpatialLocationCalculatorData::setTimestampDevice( std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } SpatialLocationCalculatorData& SpatialLocationCalculatorData::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/TrackedFeatures.cpp b/src/pipeline/datatype/TrackedFeatures.cpp index 7e3361c9c..81ad8ddaa 100644 --- a/src/pipeline/datatype/TrackedFeatures.cpp +++ b/src/pipeline/datatype/TrackedFeatures.cpp @@ -11,39 +11,17 @@ TrackedFeatures::TrackedFeatures() TrackedFeatures::TrackedFeatures(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), trackedFeatures(rawdata.trackedFeatures) {} -// getters -std::chrono::time_point TrackedFeatures::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point TrackedFeatures::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t TrackedFeatures::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters TrackedFeatures& TrackedFeatures::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } TrackedFeatures& TrackedFeatures::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } TrackedFeatures& TrackedFeatures::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/Tracklets.cpp b/src/pipeline/datatype/Tracklets.cpp index 7efc931a6..d6c282efd 100644 --- a/src/pipeline/datatype/Tracklets.cpp +++ b/src/pipeline/datatype/Tracklets.cpp @@ -10,39 +10,17 @@ Tracklets::Tracklets() : Buffer(std::make_shared()), rawdata(*dyna Tracklets::Tracklets(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), tracklets(rawdata.tracklets) {} -// getters -std::chrono::time_point Tracklets::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point Tracklets::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t Tracklets::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters Tracklets& Tracklets::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } Tracklets& Tracklets::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } Tracklets& Tracklets::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai From 5198e8b6e177e5be00e16ae3a6d0e9090267ee20 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 17 Aug 2023 16:33:22 +0300 Subject: [PATCH 26/63] FW: add support for OAK-D-SR-PoE R1M1E1 --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index bbaddb7ec..12b6526c1 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "1d4e70a72c7eb43692fa4dfac200436573089741") +set(DEPTHAI_DEVICE_SIDE_COMMIT "dc787ceb84ba5d0e878cf3d5fe5a8d79282e9fb6") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 05cb121914ef42aec04d2ff9aeef778f58a11b52 Mon Sep 17 00:00:00 2001 From: asahtik Date: Thu, 17 Aug 2023 16:02:24 +0200 Subject: [PATCH 27/63] Fixed mistake in ImgFrame --- src/pipeline/datatype/ImgFrame.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/pipeline/datatype/ImgFrame.cpp b/src/pipeline/datatype/ImgFrame.cpp index fda7a4899..279c72ccd 100644 --- a/src/pipeline/datatype/ImgFrame.cpp +++ b/src/pipeline/datatype/ImgFrame.cpp @@ -31,7 +31,7 @@ std::chrono::time_point ImgFrame::getTimestampDevice(CameraExposureOffset offset) const { - auto ts = getTimestamp(); + auto ts = getTimestampDevice(); auto expTime = getExposureTime(); switch(offset) { case CameraExposureOffset::START: From f09e7ee7f10cfb61ab677d907a5a04b997382bf2 Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 18 Aug 2023 09:35:14 +0200 Subject: [PATCH 28/63] Ran ClangFormat --- include/depthai/device/DeviceBase.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index f93bb6675..569b68c9b 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -364,7 +364,7 @@ class DeviceBase { /** * Connects to device specified by devInfo. - * @param config Config with which the device will be booted with + * @param config Config with which the device will be booted with * @param devInfo DeviceInfo which specifies which device to connect to * @param maxUsbSpeed Maximum allowed USB speed */ From a568ab6e037a9434abbdd39b2b460c7b3233e6c2 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Mon, 21 Aug 2023 09:29:18 +0200 Subject: [PATCH 29/63] Added DEPTHAI_ENABLE_LIBUSB option, to enable/disable USB protocol in build time --- CMakeLists.txt | 13 ++++++++++--- cmake/Hunter/config.cmake | 6 ++++-- cmake/config.hpp.in | 23 +++++++++++++++++++++++ examples/CMakeLists.txt | 3 ++- src/utility/Initialization.cpp | 14 +++++++++++--- tests/CMakeLists.txt | 3 ++- 6 files changed, 52 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index dc2972914..c32131618 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,6 +6,9 @@ if(NOT WIN32) set(HUNTER_CONFIGURATION_TYPES "Release" CACHE STRING "Hunter dependencies list of build configurations") endif() +# Early options +option(DEPTHAI_ENABLE_LIBUSB "Enable usage of libusb and interaction with USB devices" ON) + # Set type to canonicalize relative paths for user-provided toolchain set(CMAKE_TOOLCHAIN_FILE "" CACHE FILEPATH "CMake toolchain path") @@ -446,13 +449,16 @@ target_link_libraries(${TARGET_CORE_NAME} set(DEPTHAI_DEVICE_VERSION "${DEPTHAI_DEVICE_SIDE_COMMIT}") target_compile_definitions(${TARGET_CORE_NAME} PRIVATE - # XLink required define - __PC__ # Add depthai-device version DEPTHAI_DEVICE_VERSION="${DEPTHAI_DEVICE_VERSION}" # Add depthai-bootloader version DEPTHAI_BOOTLOADER_VERSION="${DEPTHAI_BOOTLOADER_VERSION}" ) +# Add compile flag if libusb is available +if(DEPTHAI_ENABLE_LIBUSB) + target_compile_definitions(${TARGET_CORE_NAME} PRIVATE DEPTHAI_ENABLE_LIBUSB) + set(DEPTHAI_HAVE_LIBUSB_SUPPORT ON) +endif() # Add Backward dependency if enabled (On by default) if(DEPTHAI_ENABLE_BACKWARD) @@ -481,8 +487,9 @@ macro(add_runtime_dependencies depending_target dependency) set(required_dll_files ${dlls} ${depthai_dll_libraries}) # Copy the required dlls add_custom_command(TARGET ${depending_target} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${required_dll_files} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${required_dll_files};$>" COMMAND_EXPAND_LISTS + VERBATIM ) message(STATUS "Required dlls for core are: ${required_dll_files}") endif() diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 5142bc426..4d059aab4 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -8,8 +8,10 @@ hunter_config( hunter_config( XLink VERSION "luxonis-2021.4.2-develop" - URL "https://github.com/luxonis/XLink/archive/457b23fb33e1146610e1a4e52defa7565046977a.tar.gz" - SHA1 "006a2bd391498aea7895e988b787a420e7f51fa9" + URL "https://github.com/luxonis/XLink/archive/48db5dc9d1d7edda34da03c07cd30c292c962080.tar.gz" + SHA1 "2d274574af8167d8a799ca3e1117291bc6998b36" + CMAKE_ARGS + XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB} ) hunter_config( diff --git a/cmake/config.hpp.in b/cmake/config.hpp.in index 6e1efb741..97cc44bfc 100644 --- a/cmake/config.hpp.in +++ b/cmake/config.hpp.in @@ -6,9 +6,32 @@ // This build supports OpenCV integration? #cmakedefine DEPTHAI_HAVE_OPENCV_SUPPORT +// This build supports libusb? +#cmakedefine DEPTHAI_HAVE_LIBUSB_SUPPORT + // Build specific settings overwrite #ifdef DEPTHAI_TARGET_CORE #ifndef DEPTHAI_TARGET_OPENCV #undef DEPTHAI_HAVE_OPENCV_SUPPORT #endif #endif + +namespace dai +{ +namespace build +{ + +#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT + constexpr static bool HAVE_OPENCV_SUPPORT = true; +#else + constexpr static bool HAVE_OPENCV_SUPPORT = false; +#endif + +#ifdef DEPTHAI_HAVE_LIBUSB_SUPPORT + constexpr static bool HAVE_LIBUSB_SUPPORT = true; +#else + constexpr static bool HAVE_LIBUSB_SUPPORT = false; +#endif + +} // namespace build +} // namespace dai diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index e3b910291..1be23d128 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -83,8 +83,9 @@ function(dai_add_example example_name example_src enable_test) set(depthai_dll_libraries "$") endif() add_custom_command(TARGET ${example_name} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${depthai_dll_libraries} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${depthai_dll_libraries};$>" COMMAND_EXPAND_LISTS + VERBATIM ) endif() endfunction() diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index 931cb7f5c..5225ed6aa 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -4,6 +4,7 @@ #include // project +#include "build/config.hpp" #include "build/version.hpp" #include "utility/Environment.hpp" #include "utility/Logging.hpp" @@ -81,8 +82,12 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav if(additionalInfo != nullptr && additionalInfo[0] != '\0') { logger::debug("{}", additionalInfo); } - logger::debug( - "Library information - version: {}, commit: {} from {}, build: {}", build::VERSION, build::COMMIT, build::COMMIT_DATETIME, build::BUILD_DATETIME); + logger::debug("Library information - version: {}, commit: {} from {}, build: {}, libusb enabled: {}", + build::VERSION, + build::COMMIT, + build::COMMIT_DATETIME, + build::BUILD_DATETIME, + build::HAVE_LIBUSB_SUPPORT); // Executed at library load time @@ -104,10 +109,13 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav logger::debug("Initialize failed - {}", errorMsg); throw std::runtime_error(errorMsg); } - // Check that USB protocol is available + + // Check that USB protocol is available, IFF libusb is enabled +#ifdef DEPTHAI_ENABLE_LIBUSB if(!XLinkIsProtocolInitialized(X_LINK_USB_VSC)) { logger::warn("USB protocol not available - {}", ERROR_MSG_USB_TIP); } +#endif // Enable Global XLink profiling XLinkProfStart(); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 21260e2f8..fc8bc81da 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -107,8 +107,9 @@ function(dai_add_test test_name test_src) set(depthai_dll_libraries "$") endif() add_custom_command(TARGET ${test_name} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${depthai_dll_libraries} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${depthai_dll_libraries};$>" COMMAND_EXPAND_LISTS + VERBATIM ) endif() endfunction() From 4310b9ded5ac2e09b69ab853a982646d0cb0df99 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Mon, 21 Aug 2023 09:29:27 +0200 Subject: [PATCH 30/63] Applied style --- include/depthai/device/DeviceBase.hpp | 2 +- tests/src/device_usbspeed_test.cpp | 6 ++---- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index f93bb6675..569b68c9b 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -364,7 +364,7 @@ class DeviceBase { /** * Connects to device specified by devInfo. - * @param config Config with which the device will be booted with + * @param config Config with which the device will be booted with * @param devInfo DeviceInfo which specifies which device to connect to * @param maxUsbSpeed Maximum allowed USB speed */ diff --git a/tests/src/device_usbspeed_test.cpp b/tests/src/device_usbspeed_test.cpp index 21237a0aa..8605b1425 100644 --- a/tests/src/device_usbspeed_test.cpp +++ b/tests/src/device_usbspeed_test.cpp @@ -53,8 +53,7 @@ TEST_CASE("UsbSpeed::SUPER_PLUS") { verifyInfo(d); } -TEST_CASE("Pipeline config usb speed == SUPER") -{ +TEST_CASE("Pipeline config usb speed == SUPER") { dai::Pipeline p; makeInfo(p); @@ -70,8 +69,7 @@ TEST_CASE("Pipeline config usb speed == SUPER") verifyInfo(d); } -TEST_CASE("Pipeline config usb speed == HIGH") -{ +TEST_CASE("Pipeline config usb speed == HIGH") { dai::Pipeline p; makeInfo(p); From 5e653002a4982428518ee12f98ea565e186e2386 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Mon, 21 Aug 2023 10:04:40 +0200 Subject: [PATCH 31/63] Updated XLink library with some fixes --- cmake/Hunter/config.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 4d059aab4..0bf9ae4a3 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -8,8 +8,8 @@ hunter_config( hunter_config( XLink VERSION "luxonis-2021.4.2-develop" - URL "https://github.com/luxonis/XLink/archive/48db5dc9d1d7edda34da03c07cd30c292c962080.tar.gz" - SHA1 "2d274574af8167d8a799ca3e1117291bc6998b36" + URL "https://github.com/luxonis/XLink/archive/be9171eb793b8c1b0544556fc81dc5f503815185.tar.gz" + SHA1 "35e0a5afc2074d599461336e1e55e7f77f490358" CMAKE_ARGS XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB} ) From 26cc2fb5282afc3a467f39aa0ec709f5d22a11ed Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 23 Aug 2023 11:38:05 -0400 Subject: [PATCH 32/63] FW: fix default fsync on OAK-D-SR-PoE. GPIO46 input by default --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 12b6526c1..64d58e613 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "dc787ceb84ba5d0e878cf3d5fe5a8d79282e9fb6") +set(DEPTHAI_DEVICE_SIDE_COMMIT "aab183746ea27261c159fd71681b55f65232e2db") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 517ce9384e4de25bec81eff31b390726a429d76f Mon Sep 17 00:00:00 2001 From: Aniel Alexa Date: Thu, 24 Aug 2023 18:11:49 +0300 Subject: [PATCH 33/63] hasautofocusIC --- include/depthai/common/CameraFeatures.hpp | 1 + shared/depthai-shared | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/include/depthai/common/CameraFeatures.hpp b/include/depthai/common/CameraFeatures.hpp index 3c552b4ff..a38e08d37 100644 --- a/include/depthai/common/CameraFeatures.hpp +++ b/include/depthai/common/CameraFeatures.hpp @@ -24,6 +24,7 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraFeatures& ca } out << "], "; out << "hasAutofocus: " << camera.hasAutofocus << ", "; + out << "hasAutofocusIC: " << camera.hasAutofocusIC << ", "; out << "name: " << camera.name << "}"; return out; diff --git a/shared/depthai-shared b/shared/depthai-shared index 14c99ac36..5f823e0ae 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 14c99ac36195e88800cbee7fb55497dc762b12c6 +Subproject commit 5f823e0aec1a3c62561ef4b0aef1f43298c1a79f From 0343e428d65f0417123b4b6b0dc608a4faf1107b Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 28 Aug 2023 11:06:51 -0400 Subject: [PATCH 34/63] FW: fix 4 cams crash on PoE due to memory allocation --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 64d58e613..d8ac1b02c 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "aab183746ea27261c159fd71681b55f65232e2db") +set(DEPTHAI_DEVICE_SIDE_COMMIT "b69355584145e975d19651462c33118647c7c64c") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From cd9d88360016dee55ddebf6a8d69e3d15bd6f465 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Thu, 31 Aug 2023 04:10:23 +0300 Subject: [PATCH 35/63] Update FW / shared --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- shared/depthai-shared | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index d8ac1b02c..cf8328086 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "b69355584145e975d19651462c33118647c7c64c") +set(DEPTHAI_DEVICE_SIDE_COMMIT "d1ac0b303a326eff76b7518b0626c55cf8ba0a0a") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/shared/depthai-shared b/shared/depthai-shared index 14c99ac36..8eda9270b 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 14c99ac36195e88800cbee7fb55497dc762b12c6 +Subproject commit 8eda9270bc831850df658292c2e4276218f9081d From 47055d5270b13adbb740cb1a897b7f9fe7a98aa5 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 31 Aug 2023 21:08:45 +0300 Subject: [PATCH 36/63] FW: fix OAK-D-SR camera enum. IMX296 updates: - support for RPi GS Cam paired with Luxonis SL6996 RPi camera adapter - support for external trigger on XTR/XTRIG pin: active low, pulse width determines exposure time. Limitation: needs an initial trigger shortly after start to avoid a crash, or `DEPTHAI_WATCHDOG=0` can be a workaround --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index b9154da8b..41a61d432 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "1d4f2c5443b1ae2dd3d7d394da7487158c75246c") +set(DEPTHAI_DEVICE_SIDE_COMMIT "7bb1b76021f46a599ffda2bbe9443027a88242df") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From fd3f4d7e1d49865e1d76fcffe14b63453a2f9c9e Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 1 Sep 2023 08:36:07 +0300 Subject: [PATCH 37/63] Attempt to fix serialization error on windows compiler --- shared/depthai-shared | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/depthai-shared b/shared/depthai-shared index ccff8f5eb..cb1bb4540 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit ccff8f5ebc4cd5c68cdd7faed6036f24ae617bb1 +Subproject commit cb1bb4540a6ffb4894b99155ba925e6eacdf0bc9 From 1c5fe7d075e67d5c722ab2851218582404eac35a Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Fri, 1 Sep 2023 14:07:46 +0300 Subject: [PATCH 38/63] Update FW --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 41a61d432..c9e9019cf 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "7bb1b76021f46a599ffda2bbe9443027a88242df") +set(DEPTHAI_DEVICE_SIDE_COMMIT "ef924fe490d6608fd624e89a7bf3f47e6fcb0b89") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From f7acca2387935fa0ee5bc4cd8c8eb3d65ff6ee5e Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 1 Sep 2023 19:13:53 +0200 Subject: [PATCH 39/63] Implemented timesync optimization --- include/depthai/xlink/XLinkStream.hpp | 4 ++-- src/device/DeviceBase.cpp | 10 +++------- src/xlink/XLinkStream.cpp | 8 ++++---- 3 files changed, 9 insertions(+), 13 deletions(-) diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index 47bc9ace2..3f0279d43 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -54,8 +54,8 @@ class XLinkStream { void write(const void* data, std::size_t size); void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); - std::vector read(); - void read(std::vector& data); + std::vector read(struct timespec* out_time = NULL); + void read(std::vector& data, struct timespec* out_time = NULL); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index a2bb2ddcb..ac995e19e 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -846,15 +846,11 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(d).count(); - timestamp.nsec = duration_cast(d).count() % 1000000000; + struct timespec treceive; + stream.read(&treceive); // Write timestamp back - stream.write(×tamp, sizeof(timestamp)); + stream.write(&treceive, sizeof(timestamp)); } } catch(const std::exception& ex) { // ignore diff --git a/src/xlink/XLinkStream.cpp b/src/xlink/XLinkStream.cpp index fa9393dee..576293f2d 100644 --- a/src/xlink/XLinkStream.cpp +++ b/src/xlink/XLinkStream.cpp @@ -89,18 +89,18 @@ void XLinkStream::write(const std::vector& data) { write(data.data(), data.size()); } -void XLinkStream::read(std::vector& data) { +void XLinkStream::read(std::vector& data, struct timespec* out_time) { StreamPacketDesc packet; - const auto status = XLinkReadMoveData(streamId, &packet); + const auto status = XLinkReadMoveDataWithTime(streamId, &packet, out_time); if(status != X_LINK_SUCCESS) { throw XLinkReadError(status, streamName); } data = std::vector(packet.data, packet.data + packet.length); } -std::vector XLinkStream::read() { +std::vector XLinkStream::read(struct timespec* out_time) { std::vector data; - read(data); + read(data, out_time); return data; } From 025b8d83d44ea59e2e1e0d0ab00a9187f4811bd3 Mon Sep 17 00:00:00 2001 From: asahtik Date: Thu, 7 Sep 2023 14:15:43 +0200 Subject: [PATCH 40/63] Fixed new timesync bugs --- include/depthai/xlink/XLinkStream.hpp | 6 +++--- src/device/DeviceBase.cpp | 10 +++++++--- src/xlink/XLinkStream.cpp | 10 +++++----- 3 files changed, 15 insertions(+), 11 deletions(-) diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index 3f0279d43..6dc891773 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -25,7 +25,7 @@ namespace dai { class StreamPacketDesc : public streamPacketDesc_t { public: - StreamPacketDesc() noexcept : streamPacketDesc_t{nullptr, 0} {}; + StreamPacketDesc() noexcept : streamPacketDesc_t{nullptr, 0, {}, {}} {}; StreamPacketDesc(const StreamPacketDesc&) = delete; StreamPacketDesc(StreamPacketDesc&& other) noexcept; StreamPacketDesc& operator=(const StreamPacketDesc&) = delete; @@ -54,8 +54,8 @@ class XLinkStream { void write(const void* data, std::size_t size); void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); - std::vector read(struct timespec* out_time = NULL); - void read(std::vector& data, struct timespec* out_time = NULL); + std::vector read(); + void read(std::vector& data); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index ac995e19e..1aeb648c6 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -846,11 +846,15 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(d).count(); + timestamp.nsec = duration_cast(d).count() % 1000000000; // Write timestamp back - stream.write(&treceive, sizeof(timestamp)); + stream.write(×tamp, sizeof(timestamp)); } } catch(const std::exception& ex) { // ignore diff --git a/src/xlink/XLinkStream.cpp b/src/xlink/XLinkStream.cpp index 576293f2d..a09f979c9 100644 --- a/src/xlink/XLinkStream.cpp +++ b/src/xlink/XLinkStream.cpp @@ -54,7 +54,7 @@ XLinkStream::~XLinkStream() { } } -StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length} { +StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length, {}, {}} { other.data = nullptr; other.length = 0; } @@ -89,18 +89,18 @@ void XLinkStream::write(const std::vector& data) { write(data.data(), data.size()); } -void XLinkStream::read(std::vector& data, struct timespec* out_time) { +void XLinkStream::read(std::vector& data) { StreamPacketDesc packet; - const auto status = XLinkReadMoveDataWithTime(streamId, &packet, out_time); + const auto status = XLinkReadMoveData(streamId, &packet); if(status != X_LINK_SUCCESS) { throw XLinkReadError(status, streamName); } data = std::vector(packet.data, packet.data + packet.length); } -std::vector XLinkStream::read(struct timespec* out_time) { +std::vector XLinkStream::read() { std::vector data; - read(data, out_time); + read(data); return data; } From 803f2429d3d29877a6fe6565a4d6d1af264a7707 Mon Sep 17 00:00:00 2001 From: asahtik Date: Thu, 7 Sep 2023 15:10:55 +0200 Subject: [PATCH 41/63] Moved treceive back to XLink --- include/depthai/xlink/XLinkStream.hpp | 4 ++-- src/device/DeviceBase.cpp | 9 ++------- src/xlink/XLinkStream.cpp | 12 ++++++++---- 3 files changed, 12 insertions(+), 13 deletions(-) diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index 6dc891773..9b4ed8adb 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -54,8 +54,8 @@ class XLinkStream { void write(const void* data, std::size_t size); void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); - std::vector read(); - void read(std::vector& data); + std::vector read(struct timespec* out_time=NULL); + void read(std::vector& data, struct timespec* out_time=NULL); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 1aeb648c6..56012f172 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -843,15 +843,10 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(d).count(); - timestamp.nsec = duration_cast(d).count() % 1000000000; + struct timespec timestamp; + stream.read(×tamp); // Write timestamp back stream.write(×tamp, sizeof(timestamp)); diff --git a/src/xlink/XLinkStream.cpp b/src/xlink/XLinkStream.cpp index a09f979c9..b5603e390 100644 --- a/src/xlink/XLinkStream.cpp +++ b/src/xlink/XLinkStream.cpp @@ -54,7 +54,7 @@ XLinkStream::~XLinkStream() { } } -StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length, {}, {}} { +StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length, other.trsend, other.treceive} { other.data = nullptr; other.length = 0; } @@ -63,6 +63,8 @@ StreamPacketDesc& StreamPacketDesc::operator=(StreamPacketDesc&& other) noexcept if(this != &other) { data = std::exchange(other.data, nullptr); length = std::exchange(other.length, 0); + trsend = std::exchange(other.trsend, {}); + treceive = std::exchange(other.treceive, {}); } return *this; } @@ -89,18 +91,20 @@ void XLinkStream::write(const std::vector& data) { write(data.data(), data.size()); } -void XLinkStream::read(std::vector& data) { +void XLinkStream::read(std::vector& data, struct timespec* out_time) { StreamPacketDesc packet; const auto status = XLinkReadMoveData(streamId, &packet); if(status != X_LINK_SUCCESS) { throw XLinkReadError(status, streamName); } data = std::vector(packet.data, packet.data + packet.length); + if(out_time != NULL) + *out_time = packet.treceive; } -std::vector XLinkStream::read() { +std::vector XLinkStream::read(struct timespec* out_time) { std::vector data; - read(data); + read(data, out_time); return data; } From 7afad88e557a537ad713e8f854bc0ff084cc9ba8 Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 8 Sep 2023 10:12:57 +0200 Subject: [PATCH 42/63] Changes according to PR issue --- include/depthai/xlink/XLinkStream.hpp | 6 ++++-- src/device/DeviceBase.cpp | 2 +- src/xlink/XLinkStream.cpp | 30 ++++++++++++++++++++------- 3 files changed, 27 insertions(+), 11 deletions(-) diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index 9b4ed8adb..b78f96256 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -54,8 +54,10 @@ class XLinkStream { void write(const void* data, std::size_t size); void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); - std::vector read(struct timespec* out_time=NULL); - void read(std::vector& data, struct timespec* out_time=NULL); + std::vector read(); + std::vector read(struct timespec& timestampReceived); + void read(std::vector& data); + void read(std::vector& data, struct timespec& timestampReceived); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 56012f172..7ffbdd4c5 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -846,7 +846,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional& data) { write(data.data(), data.size()); } -void XLinkStream::read(std::vector& data, struct timespec* out_time) { +void XLinkStream::read(std::vector& data) { StreamPacketDesc packet; const auto status = XLinkReadMoveData(streamId, &packet); if(status != X_LINK_SUCCESS) { throw XLinkReadError(status, streamName); } data = std::vector(packet.data, packet.data + packet.length); - if(out_time != NULL) - *out_time = packet.treceive; } -std::vector XLinkStream::read(struct timespec* out_time) { +void XLinkStream::read(std::vector& data, struct timespec& timestampReceived) { + StreamPacketDesc packet; + const auto status = XLinkReadMoveData(streamId, &packet); + if(status != X_LINK_SUCCESS) { + throw XLinkReadError(status, streamName); + } + data = std::vector(packet.data, packet.data + packet.length); + timestampReceived = packet.tReceived; +} + +std::vector XLinkStream::read() { + std::vector data; + read(data); + return data; +} + +std::vector XLinkStream::read(struct timespec& timestampReceived) { std::vector data; - read(data, out_time); + read(data, timestampReceived); return data; } From bdfa86d5d61585eed99378100f42fc5fee854211 Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 8 Sep 2023 12:04:06 +0200 Subject: [PATCH 43/63] Clangformat --- src/device/DeviceBase.cpp | 2 +- src/openvino/BlobReader.cpp | 2 +- src/utility/Path.cpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 7ffbdd4c5..3f7bb4559 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -846,7 +846,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional +// #include namespace dai { diff --git a/src/utility/Path.cpp b/src/utility/Path.cpp index f7b625530..fe0b970e8 100644 --- a/src/utility/Path.cpp +++ b/src/utility/Path.cpp @@ -10,13 +10,13 @@ namespace dai { std::wstring Path::convert_utf8_to_wide(const std::string& utf8string) { - //#pragma warning(suppress : 4996) + // #pragma warning(suppress : 4996) std::wstring_convert> converter; return converter.from_bytes(utf8string); } std::string Path::u8string() const { - //#pragma warning(suppress : 4996) + // #pragma warning(suppress : 4996) std::wstring_convert> converter; return converter.to_bytes(_nativePath); } From a4ec9279b8d4fbdb3ccfa5c5872d5c7c2ea245b4 Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 8 Sep 2023 12:25:21 +0200 Subject: [PATCH 44/63] Bump FW --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index c9e9019cf..d907c33cb 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "ef924fe490d6608fd624e89a7bf3f47e6fcb0b89") +set(DEPTHAI_DEVICE_SIDE_COMMIT "16bb073ae70ad6d79e8e0e319587155a2a75be53") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 3af7c38878e9ff6eecd07d0760d8c4a0b9dc5a82 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Tue, 12 Sep 2023 23:11:14 +0200 Subject: [PATCH 45/63] WIP: Device name improvements --- src/device/DeviceBase.cpp | 87 ++++++++++++++++++++++++++++++--------- 1 file changed, 68 insertions(+), 19 deletions(-) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index a2bb2ddcb..9a3dc83d9 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -1067,31 +1067,80 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } +static std::vector split(const std::string& s, char delimiter) { + std::vector tokens; + size_t start = 0; + size_t end = s.find(delimiter); + + while (end != std::string::npos) { + tokens.push_back(s.substr(start, end - start)); + start = end + 1; + end = s.find(delimiter, start); + } + + tokens.push_back(s.substr(start, end)); + + return tokens; +} + std::string DeviceBase::getDeviceName() { std::string deviceName; - EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - eeprom = readCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - deviceName = eeprom.boardName; + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + std::string productNameOrFallback; + if((productNameOrFallback = eepromFactory.productName).empty()) { + if((productNameOrFallback = eeprom.productName).empty()) { + productNameOrFallback = eeprom.boardName; } } - - // Convert to device naming from display/product naming - // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); - std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); - std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); - - // Handle some known legacy cases - if(deviceName == "BW1098OBC") { - deviceName = "OAK-D"; - } else if(deviceName == "DM2097") { - deviceName = "OAK-D-CM4-POE"; - } else if(deviceName == "BW1097") { - deviceName = "OAK-D-CM3"; + bool hasDeviceName = true; + deviceName = productNameOrFallback; + if((deviceName = eepromFactory.deviceName).empty()) { + if((deviceName = eeprom.deviceName).empty()) { + deviceName = productNameOrFallback; + hasDeviceName = false; + } } - return deviceName; + if(hasDeviceName) { + return deviceName; + } else { + + // Convert to device naming from display/product naming + // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); + std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); + std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); + + // Handle some known legacy cases + if(deviceName == "BW1098OBC") { + deviceName = "OAK-D"; + } else if(deviceName == "DM2097") { + deviceName = "OAK-D-CM4-POE"; + } else if(deviceName == "BW1097") { + deviceName = "OAK-D-CM3"; + } + + std::vector skuDiff = { + "AF", "FF", "97", "OV9782" + }; + + // Regenerate from tokens + auto tokens = split(deviceName, '-'); + deviceName = ""; + for(int i = 0; i < tokens.size(); i++) { + const auto& token = tokens[i]; + + // check if token has to be removed + for(const auto& d : skuDiff) { + if(token == d) continue; + } + + if(i != 0) deviceName += "-"; + deviceName += token; + } + + return deviceName; + } } void DeviceBase::setLogOutputLevel(LogLevel level) { From d841b96fc3290092ef664c9634dd1b3efaf3764c Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Tue, 12 Sep 2023 23:13:52 +0200 Subject: [PATCH 46/63] Added improvements to device naming --- CMakeLists.txt | 1 + include/depthai/device/CalibrationHandler.hpp | 31 +++++ include/depthai/device/DeviceBase.hpp | 6 + shared/depthai-shared | 2 +- src/device/CalibrationHandler.cpp | 40 +++++- src/device/DeviceBase.cpp | 79 ++---------- src/utility/EepromDataParser.cpp | 88 ++++++++++++++ src/utility/EepromDataParser.hpp | 29 +++++ tests/CMakeLists.txt | 3 + tests/src/naming_test.cpp | 115 ++++++++++++++++++ 10 files changed, 321 insertions(+), 73 deletions(-) create mode 100644 src/utility/EepromDataParser.cpp create mode 100644 src/utility/EepromDataParser.hpp create mode 100644 tests/src/naming_test.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index c32131618..3a7ad0371 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -254,6 +254,7 @@ add_library(${TARGET_CORE_NAME} src/utility/Environment.cpp src/utility/XLinkGlobalProfilingLogger.cpp src/utility/Logging.cpp + src/utility/EepromDataParser.cpp src/xlink/XLinkConnection.cpp src/xlink/XLinkStream.cpp src/openvino/OpenVINO.cpp diff --git a/include/depthai/device/CalibrationHandler.hpp b/include/depthai/device/CalibrationHandler.hpp index 04ba756dd..8104707d6 100644 --- a/include/depthai/device/CalibrationHandler.hpp +++ b/include/depthai/device/CalibrationHandler.hpp @@ -353,6 +353,37 @@ class CalibrationHandler { uint32_t boardOptions, std::string boardCustom = ""); + /** + * Set the Board Info object. Creates version 7 EEPROM data + * + * @param deviceName Sets device name. + * @param productName Sets product name (alias). + * @param boardName Sets board name. + * @param boardRev Sets board revision id. + * @param boardConf Sets board configuration id. + * @param hardwareConf Sets hardware configuration id. + * @param batchName Sets batch name. + * @param batchTime Sets batch time (unix timestamp). + * @param boardCustom Sets a custom board (Default empty string). + */ + void setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom = ""); + + /** + * Set the deviceName which responses to getDeviceName of Device + * + * @param deviceName Sets device name. + */ + void setDeviceName(std::string productName); + /** * Set the productName which acts as alisas for users to identify the device * diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 569b68c9b..327f726fe 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -456,6 +456,12 @@ class DeviceBase { */ std::string getDeviceName(); + /** + * Get product name if available + * @returns product name or empty string if not available + */ + std::string getProductName(); + /** * Get MxId of device * diff --git a/shared/depthai-shared b/shared/depthai-shared index cb1bb4540..2c88c8780 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit cb1bb4540a6ffb4894b99155ba925e6eacdf0bc9 +Subproject commit 2c88c8780ccd3ac66011c85406fa0d46239096eb diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 15a4b6a29..c71d880c5 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -560,11 +560,49 @@ void CalibrationHandler::setBoardInfo(std::string productName, eepromData.boardRev = boardRev; eepromData.boardConf = boardConf; eepromData.hardwareConf = hardwareConf; - eepromData.batchName = batchName; eepromData.batchTime = batchTime; eepromData.boardCustom = boardCustom; eepromData.boardOptions = boardOptions; + if(batchName != "") { + logger::warn("batchTime parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom) { + eepromData.productName = productName; + eepromData.boardName = boardName; + eepromData.boardRev = boardRev; + eepromData.boardConf = boardConf; + eepromData.hardwareConf = hardwareConf; + eepromData.batchTime = batchTime; + eepromData.boardCustom = boardCustom; + eepromData.boardOptions = boardOptions; + eepromData.deviceName = deviceName; + + if(batchName != "") { + logger::warn("batchTime parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setDeviceName(std::string deviceName) { + eepromData.deviceName = deviceName; + // Bump version to V7 eepromData.version = 7; } diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 9a3dc83d9..497e9d660 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -25,6 +25,7 @@ #include "utility/Initialization.hpp" #include "utility/PimplImpl.hpp" #include "utility/Resources.hpp" +#include "utility/EepromDataParser.hpp" // libraries #include "XLink/XLink.h" @@ -922,8 +923,8 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(w / rate); + r = static_cast(r / rate); lastData = data; @@ -1067,80 +1068,16 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } -static std::vector split(const std::string& s, char delimiter) { - std::vector tokens; - size_t start = 0; - size_t end = s.find(delimiter); - - while (end != std::string::npos) { - tokens.push_back(s.substr(start, end - start)); - start = end + 1; - end = s.find(delimiter, start); - } - - tokens.push_back(s.substr(start, end)); - - return tokens; +std::string DeviceBase::getProductName() { + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + return utility::parseProductName(eeprom, eepromFactory); } std::string DeviceBase::getDeviceName() { - std::string deviceName; EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); EepromData eeprom = readCalibrationOrDefault().getEepromData(); - std::string productNameOrFallback; - if((productNameOrFallback = eepromFactory.productName).empty()) { - if((productNameOrFallback = eeprom.productName).empty()) { - productNameOrFallback = eeprom.boardName; - } - } - bool hasDeviceName = true; - deviceName = productNameOrFallback; - if((deviceName = eepromFactory.deviceName).empty()) { - if((deviceName = eeprom.deviceName).empty()) { - deviceName = productNameOrFallback; - hasDeviceName = false; - } - } - - if(hasDeviceName) { - return deviceName; - } else { - - // Convert to device naming from display/product naming - // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); - std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); - std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); - - // Handle some known legacy cases - if(deviceName == "BW1098OBC") { - deviceName = "OAK-D"; - } else if(deviceName == "DM2097") { - deviceName = "OAK-D-CM4-POE"; - } else if(deviceName == "BW1097") { - deviceName = "OAK-D-CM3"; - } - - std::vector skuDiff = { - "AF", "FF", "97", "OV9782" - }; - - // Regenerate from tokens - auto tokens = split(deviceName, '-'); - deviceName = ""; - for(int i = 0; i < tokens.size(); i++) { - const auto& token = tokens[i]; - - // check if token has to be removed - for(const auto& d : skuDiff) { - if(token == d) continue; - } - - if(i != 0) deviceName += "-"; - deviceName += token; - } - - return deviceName; - } + return utility::parseDeviceName(eeprom, eepromFactory); } void DeviceBase::setLogOutputLevel(LogLevel level) { diff --git a/src/utility/EepromDataParser.cpp b/src/utility/EepromDataParser.cpp new file mode 100644 index 000000000..502a7329c --- /dev/null +++ b/src/utility/EepromDataParser.cpp @@ -0,0 +1,88 @@ +#include "utility/EepromDataParser.hpp" + +namespace dai +{ +namespace utility +{ + +std::vector split(const std::string& s, char delimiter) { + std::vector tokens; + size_t start = 0; + size_t end = s.find(delimiter); + + while (end != std::string::npos) { + tokens.push_back(s.substr(start, end - start)); + start = end + 1; + end = s.find(delimiter, start); + } + + tokens.push_back(s.substr(start, end)); + + return tokens; +} + +std::string parseProductName(EepromData eeprom, EepromData eepromFactory) { + std::string productName; + if((productName = eepromFactory.productName).empty()) { + if((productName = eeprom.productName).empty()) { + productName = eeprom.boardName; + } + } + + // Convert to device naming from display/product naming + std::transform(productName.begin(), productName.end(), productName.begin(), [](int c) { return std::toupper(c); }); + std::replace(productName.begin(), productName.end(), ' ', '-'); + + // Handle some known legacy cases + if(productName == "BW1098OBC") { + productName = "OAK-D"; + } else if(productName == "DM2097") { + productName = "OAK-D-CM4-POE"; + } else if(productName == "BW1097") { + productName = "OAK-D-CM3"; + } + + return productName; +} + + +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory) { + std::string deviceName; + if((deviceName = eepromFactory.deviceName).empty()) { + if((deviceName = eeprom.deviceName).empty()) { + // Constant skuDiff array + const std::array skuDiff = {"AF", "FF", "97", "9782", "OV9782"}; + + // Parse productName and use that to generate device name + deviceName = parseProductName(eeprom, eepromFactory); + + // Regenerate from tokens + auto tokens = split(deviceName, '-'); + deviceName = ""; + for(int i = 0; i < tokens.size(); i++) { + const auto& token = tokens[i]; + + // check if token has to be removed + bool skipToken = false; + for(const auto& d : skuDiff) { + if(token == d) { + skipToken = true; + break; + } + } + if(skipToken) continue; + + if(i != 0) deviceName += "-"; + deviceName += token; + } + + // Return generated deviceName + return deviceName; + } + } + + return deviceName; +} + +} // namespace utility +} // namespace dai diff --git a/src/utility/EepromDataParser.hpp b/src/utility/EepromDataParser.hpp new file mode 100644 index 000000000..0bab9f574 --- /dev/null +++ b/src/utility/EepromDataParser.hpp @@ -0,0 +1,29 @@ +#pragma once + +#include "depthai-shared/common/EepromData.hpp" + +namespace dai +{ +namespace utility +{ + +/// @brief Splits given string by delimiter +/// @param s string to split +/// @param delimiter character by which to split +/// @return vector of split strings +std::vector split(const std::string& s, char delimiter); + +/// @brief Parses product name from given EepromData combination +/// @param eeprom EepromData containing fields to parse product name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning product name or empty +std::string parseProductName(EepromData eeprom, EepromData eepromFactory = {}); + +/// @brief Parses device name from given EepromData combination +/// @param eeprom EepromData containing fields to parse device name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning device name or empty +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory = {}); + +} // namespace utility +} // namespace dai diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index fc8bc81da..381072b80 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -217,6 +217,9 @@ dai_test_compile_definitions(openvino_blob_test PRIVATE # Bootloader configuration tests dai_add_test(bootloader_config_test src/bootloader_config_test.cpp) +# Eeprom naming parsing tests +dai_add_test(naming_test src/naming_test.cpp) + # Device USB Speed and serialization macros test dai_add_test(device_usbspeed_test src/device_usbspeed_test.cpp CONFORMING) dai_add_test(device_usbspeed_test_17 src/device_usbspeed_test.cpp CONFORMING CXX_STANDARD 17) diff --git a/tests/src/naming_test.cpp b/tests/src/naming_test.cpp new file mode 100644 index 000000000..78a49eca2 --- /dev/null +++ b/tests/src/naming_test.cpp @@ -0,0 +1,115 @@ +#include + +#include "../../src/utility/EepromDataParser.hpp" + +struct ProductDevice { + std::string oldProductName, productName, deviceName; +}; +std::vector productToDeviceNames = { + {"OAK-D LR", "OAK-D-LR", "OAK-D-LR"}, + {"OAK-D", "OAK-D", "OAK-D"}, + {"OAK-FFC 1P PoE", "OAK-FFC-1P-POE", "OAK-FFC-1P-POE"}, + {"OAK-FFC 4P", "OAK-FFC-4P", "OAK-FFC-4P"}, + {"OAK-FFC 3P", "OAK-FFC-3P", "OAK-FFC-3P"}, + {"OAK-D CM4", "OAK-D-CM4", "OAK-D-CM4"}, + {"OAK-D SR", "OAK-D-SR", "OAK-D-SR"}, + {"OAK-D PoE AF", "OAK-D-POE-AF", "OAK-D-POE"}, + {"OAK-D CM4 PoE", "OAK-D-CM4-POE", "OAK-D-CM4-POE"}, + {"rae", "RAE", "RAE"}, + {"OAK-FFC 6P", "OAK-FFC-6P", "OAK-FFC-6P"}, + {"OAK-D Lite", "OAK-D-LITE", "OAK-D-LITE"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D Pro AF", "OAK-D-PRO-AF", "OAK-D-PRO"}, + {"OAK-D Pro FF 97", "OAK-D-PRO-FF-97", "OAK-D-PRO"}, + {"OAK-D Pro FF", "OAK-D-PRO-FF", "OAK-D-PRO"}, + {"OAK-D Pro W 97", "OAK-D-PRO-W-97", "OAK-D-PRO-W"}, + {"OAK-D Pro W OV9782", "OAK-D-PRO-W-OV9782", "OAK-D-PRO-W"}, + {"OAK-D Pro W", "OAK-D-PRO-W", "OAK-D-PRO-W"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D W 97", "OAK-D-W-97", "OAK-D-W"}, + {"OAK-D SR PoE", "OAK-D-SR-POE", "OAK-D-SR-POE"}, + {"OAK-FFC-4P PoE", "OAK-FFC-4P-POE", "OAK-FFC-4P-POE"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1-FF 97", "OAK-1-FF-97", "OAK-1"}, + {"OAK-1 FF", "OAK-1-FF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W 97", "OAK-1-W-97", "OAK-1-W"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D S2 PoE AF", "OAK-D-S2-POE-AF", "OAK-D-S2-POE"}, + {"OAK-D S2 PoE FF", "OAK-D-S2-POE-FF", "OAK-D-S2-POE"}, + {"OAK-D W PoE", "OAK-D-W-POE", "OAK-D-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro W PoE 97", "OAK-D-PRO-W-POE-97", "OAK-D-PRO-W-POE"}, + {"OAK-D W PoE 97", "OAK-D-W-POE-97", "OAK-D-W-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + + // Special cases, resolved by modifying eeprom instead + // {"OAK-D PoE C22", "OAK-D-POE-C22", "OAK-D-POE"}, + // {"", "OAK-D-CM4-POE-C11", "OAK-D-CM4-POE"}, + // {"", "OAK-D-CM4-POE-C24", "OAK-D-CM4-POE"}, + //{"OAK-D Pro AF PB", "OAK-D-PRO-AF-PB", "OAK-D-PRO"}, + // {"OAK-D Pro FF C13", "OAK-D-PRO-FF-C13", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-C17", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#1", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#2", "OAK-D-PRO"}, + // {"OAK-D Pro W C06", "OAK-D-PRO-W-C06", "OAK-D-PRO-W"}, + // {"OAK-D Pro FF", "OAK-D-PRO-W-C16", "OAK-D-PRO-W"}, + // {"", "OAK-D-W-C15", "OAK-D-W"}, + // {"", "OAK-D-PRO-W-DEV", "OAK-D-PRO-W-DEV"}, + // {"", "OAK-1-LITE-C05", "OAK-1-LITE"}, + // {"OAK-1 AF", "OAK-1-AF-C20", "OAK-1"}, + // {"OAK-D Pro PoE AF C18", "OAK-D-PRO-POE-AF-C18", "OAK-D-PRO-POE-C18"}, + // {"OAK-D Pro W PoE C01", "OAK-D-PRO-W-POE-C01", "OAK-D-PRO-W-POE-C01"}, + +}; + +TEST_CASE("parsing") { + + for (size_t i = 0; i < productToDeviceNames.size(); i++) { + INFO("Testing with iteration number: " << i); + + const auto& pd = productToDeviceNames[i]; + dai::EepromData data; + data.productName = pd.productName; + + // Test parsing of device name + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + data.productName = pd.oldProductName; + REQUIRE(pd.productName == dai::utility::parseProductName(data)); + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + + // Test parsing directly to device name + data.deviceName = pd.deviceName; + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + } + +} \ No newline at end of file From 0af97a8a603ba23be7e96d617894fad1857393dd Mon Sep 17 00:00:00 2001 From: asahtik Date: Wed, 13 Sep 2023 08:43:51 +0200 Subject: [PATCH 47/63] FIXME: does not work on rpi --- src/device/DeviceBase.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 3f7bb4559..8a0aea9d2 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -845,6 +845,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional Date: Wed, 13 Sep 2023 15:31:17 +0200 Subject: [PATCH 48/63] Updated FW with changes --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index c9e9019cf..c64d3094b 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "ef924fe490d6608fd624e89a7bf3f47e6fcb0b89") +set(DEPTHAI_DEVICE_SIDE_COMMIT "3abb3431812095b38109cc48e5071cfaa10f7d9a") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From b5ac2ee89c8340e28fad770e06c2cf50232f392f Mon Sep 17 00:00:00 2001 From: asahtik Date: Wed, 13 Sep 2023 16:00:06 +0200 Subject: [PATCH 49/63] Bump shared --- shared/depthai-shared | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/depthai-shared b/shared/depthai-shared index e0abd49c0..9f6279178 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit e0abd49c0c1a10fcdf19151079c1b286f720dd26 +Subproject commit 9f6279178ea03e7fcb08b90dfe2ea3fef6ffc775 From 5e0df289e39d707065cd267a6390a54192fc1424 Mon Sep 17 00:00:00 2001 From: asahtik Date: Wed, 13 Sep 2023 16:16:28 +0200 Subject: [PATCH 50/63] Fixed compiler error --- src/utility/EepromDataParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/utility/EepromDataParser.cpp b/src/utility/EepromDataParser.cpp index 502a7329c..67804c421 100644 --- a/src/utility/EepromDataParser.cpp +++ b/src/utility/EepromDataParser.cpp @@ -59,7 +59,7 @@ std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory) { // Regenerate from tokens auto tokens = split(deviceName, '-'); deviceName = ""; - for(int i = 0; i < tokens.size(); i++) { + for(unsigned int i = 0; i < tokens.size(); i++) { const auto& token = tokens[i]; // check if token has to be removed From f4bfbf804879ca66e800b71fc73b59619927aca8 Mon Sep 17 00:00:00 2001 From: asahtik Date: Thu, 14 Sep 2023 09:32:31 +0200 Subject: [PATCH 51/63] Changed struct timespec to custom struct to fix RPI size issues --- include/depthai/xlink/XLinkStream.hpp | 5 +++-- src/device/DeviceBase.cpp | 4 ++-- src/xlink/XLinkStream.cpp | 4 ++-- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index b78f96256..9b0865425 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -17,6 +17,7 @@ // libraries #include +#include // project #include "depthai/xlink/XLinkConnection.hpp" @@ -55,9 +56,9 @@ class XLinkStream { void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); std::vector read(); - std::vector read(struct timespec& timestampReceived); + std::vector read(XLinkTimespec& timestampReceived); void read(std::vector& data); - void read(std::vector& data, struct timespec& timestampReceived); + void read(std::vector& data, XLinkTimespec& timestampReceived); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 8a0aea9d2..cdfb5e0a7 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -28,6 +28,7 @@ // libraries #include "XLink/XLink.h" +#include "XLink/XLinkTime.h" #include "nanorpc/core/client.h" #include "nanorpc/packer/nlohmann_msgpack.h" #include "spdlog/details/os.h" @@ -845,8 +846,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional& data) { data = std::vector(packet.data, packet.data + packet.length); } -void XLinkStream::read(std::vector& data, struct timespec& timestampReceived) { +void XLinkStream::read(std::vector& data, XLinkTimespec& timestampReceived) { StreamPacketDesc packet; const auto status = XLinkReadMoveData(streamId, &packet); if(status != X_LINK_SUCCESS) { @@ -116,7 +116,7 @@ std::vector XLinkStream::read() { return data; } -std::vector XLinkStream::read(struct timespec& timestampReceived) { +std::vector XLinkStream::read(XLinkTimespec& timestampReceived) { std::vector data; read(data, timestampReceived); return data; From 3a902393c99f77b8a5d961bb5375e5543eaf2c7a Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 15 Sep 2023 09:13:05 +0200 Subject: [PATCH 52/63] Bump shared --- shared/depthai-shared | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/depthai-shared b/shared/depthai-shared index 9f6279178..38dc9c570 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 9f6279178ea03e7fcb08b90dfe2ea3fef6ffc775 +Subproject commit 38dc9c57039bcc514791c691a92e84fe753d3627 From 57de7c0cafd5724e10adce3ca8f69c8230ac6e9c Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Fri, 15 Sep 2023 14:43:53 +0300 Subject: [PATCH 53/63] FW, ColorCamera: add new almost-full-FOV resolutions for IMX378/477, scaled: 1352x1012, 4lane-only, 1/3 scaling 2024x1520, 1/2 binning --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- shared/depthai-shared | 2 +- src/pipeline/node/ColorCamera.cpp | 22 +++++++++++++++++++++ 3 files changed, 24 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index c9e9019cf..b6efc0b2d 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "ef924fe490d6608fd624e89a7bf3f47e6fcb0b89") +set(DEPTHAI_DEVICE_SIDE_COMMIT "dc4563dc83f22b31325b5cb06b20188eb10601b0") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/shared/depthai-shared b/shared/depthai-shared index cb1bb4540..9c7bad84e 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit cb1bb4540a6ffb4894b99155ba925e6eacdf0bc9 +Subproject commit 9c7bad84eb7630a68d0b15763d0eea92cd7e35f2 diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index ff021d5ae..23d479464 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -251,6 +251,12 @@ std::tuple ColorCamera::getVideoSize() const { if(properties.resolution == ColorCameraProperties::SensorResolution::THE_1440X1080) { maxVideoWidth = 1440; } + if(properties.resolution == ColorCameraProperties::SensorResolution::THE_2024X1520) { + maxVideoWidth = 2024; + } + if(properties.resolution == ColorCameraProperties::SensorResolution::THE_1352X1012) { + maxVideoWidth = 1352; + } // Take into the account the ISP scaling int numW = properties.ispScale.horizNumerator; @@ -320,6 +326,14 @@ std::tuple ColorCamera::getStillSize() const { maxStillWidth = 1440; maxStillHeight = 1080; } + if(properties.resolution == dai::ColorCameraProperties::SensorResolution::THE_2024X1520) { + maxStillWidth = 2024; + maxStillHeight = 1520; + } + if(properties.resolution == dai::ColorCameraProperties::SensorResolution::THE_1352X1012) { + maxStillWidth = 1352; + maxStillHeight = 1012; + } // Take into the account the ISP scaling int numW = properties.ispScale.horizNumerator; @@ -399,6 +413,14 @@ std::tuple ColorCamera::getResolutionSize() const { case ColorCameraProperties::SensorResolution::THE_1440X1080: return {1440, 1080}; break; + + case ColorCameraProperties::SensorResolution::THE_2024X1520: + return {2024, 1520}; + break; + + case ColorCameraProperties::SensorResolution::THE_1352X1012: + return {1352, 1012}; + break; } return {1920, 1080}; From f93b8cbc602ddb995c5c84caa0e661933be6fca5 Mon Sep 17 00:00:00 2001 From: asahtik Date: Fri, 22 Sep 2023 10:48:28 +0200 Subject: [PATCH 54/63] Fixed incorrect warp in issue #882 --- src/pipeline/datatype/ImageManipConfig.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index f129343d5..126e6edd5 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -48,6 +48,7 @@ ImageManipConfig& ImageManipConfig::setCropRotatedRect(RotatedRect rr, bool norm ImageManipConfig& ImageManipConfig::setWarpTransformFourPoints(std::vector pt, bool normalizedCoords) { // Enable resize stage and extended flags cfg.enableResize = true; + cfg.resizeConfig.keepAspectRatio = false; cfg.resizeConfig.enableWarp4pt = true; cfg.resizeConfig.warpFourPoints = pt; cfg.resizeConfig.normalizedCoords = normalizedCoords; From 052603c088b4268c108f6a2bf7a8012accc599eb Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 22 Sep 2023 22:51:20 +0200 Subject: [PATCH 55/63] [FW] OAK-D SR PoE and ToF improvements --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index fa52497a9..890d99f1f 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "5c0832b9936055085e902098afbcfd3c33a6aba3") +set(DEPTHAI_DEVICE_SIDE_COMMIT "f6d67f68b93a105814f28627aabe843c17ca6ea0") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From b928542294770e42c1561202cefa0e8a0afc338c Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Sat, 23 Sep 2023 00:23:47 +0200 Subject: [PATCH 56/63] [FW] Improved OV9782 fps handling --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- shared/depthai-shared | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 890d99f1f..7febaf059 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "f6d67f68b93a105814f28627aabe843c17ca6ea0") +set(DEPTHAI_DEVICE_SIDE_COMMIT "3b164d7220ce82c187cfb100b27e86f269cd882b") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/shared/depthai-shared b/shared/depthai-shared index 726b38634..805b62339 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 726b3863495e9cb3d5e50eed33c218bf0652ea94 +Subproject commit 805b623396f8e32b31f5bb24b5da0873597fd41b From a441ae2877a331a95530403998b0eb224a75f51e Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Mon, 25 Sep 2023 20:59:55 +0200 Subject: [PATCH 57/63] Updated FW & XLink with backward compatible timestamping --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- cmake/Hunter/config.cmake | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 7febaf059..51e32ab4e 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "3b164d7220ce82c187cfb100b27e86f269cd882b") +set(DEPTHAI_DEVICE_SIDE_COMMIT "e8417f185496f8c9f21597bfb8613465eb2daad9") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 0a7c58bc8..8b1ec7984 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -8,8 +8,8 @@ hunter_config( hunter_config( XLink VERSION "luxonis-2021.4.2-develop" - URL "https://github.com/luxonis/XLink/archive/91d738bdf9a0b1408dc05e4a1aa86ffc46e0c080.tar.gz" - SHA1 "f67b98b3227276df1aab21441d4b31913eadf41d" + URL "https://github.com/luxonis/XLink/archive/c940feaf9321f06a7d9660f28e686a9718135f38.tar.gz" + SHA1 "52935b6ceb470ee632de3348b9d2aaa2c6c24ac0" CMAKE_ARGS XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB} ) From 66ec090801ff02b94c8289c9462a78c7eb87eeea Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 28 Sep 2023 06:17:09 +0300 Subject: [PATCH 58/63] FW: fixes for AR0234 fsync, AR0234 AE max exposure: 16->33 ms, more robust camera handling (especially in sync modes) --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 51e32ab4e..b36d86237 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "e8417f185496f8c9f21597bfb8613465eb2daad9") +set(DEPTHAI_DEVICE_SIDE_COMMIT "5c8d51b3a9e7687f113beda652036043eb530506") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 143defcfc1ee163bfeb8fb5dca1d329ab6bcfed6 Mon Sep 17 00:00:00 2001 From: saching13 Date: Thu, 28 Sep 2023 22:58:51 -0700 Subject: [PATCH 59/63] fixed the order of translation multiplication --- src/device/CalibrationHandler.cpp | 42 +++++++++++++++---------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 9e0e1a22a..2291878c3 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -419,24 +419,24 @@ std::vector> CalibrationHandler::getImuToCameraExtrinsics(Cam throw std::runtime_error("There is no Camera data available corresponding to the requested source cameraId"); } - std::vector> transformationMatrix = eepromData.imuExtrinsics.rotationMatrix; + std::vector> currTransformationMatrixImu = eepromData.imuExtrinsics.rotationMatrix; if(useSpecTranslation) { - transformationMatrix[0].push_back(eepromData.imuExtrinsics.specTranslation.x); - transformationMatrix[1].push_back(eepromData.imuExtrinsics.specTranslation.y); - transformationMatrix[2].push_back(eepromData.imuExtrinsics.specTranslation.z); + currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.specTranslation.x); + currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.specTranslation.y); + currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.specTranslation.z); } else { - transformationMatrix[0].push_back(eepromData.imuExtrinsics.translation.x); - transformationMatrix[1].push_back(eepromData.imuExtrinsics.translation.y); - transformationMatrix[2].push_back(eepromData.imuExtrinsics.translation.z); + currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.translation.x); + currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.translation.y); + currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.translation.z); } std::vector homogeneous_vector = {0, 0, 0, 1}; - transformationMatrix.push_back(homogeneous_vector); + currTransformationMatrixImu.push_back(homogeneous_vector); if(eepromData.imuExtrinsics.toCameraSocket == cameraId) { - return transformationMatrix; + return currTransformationMatrixImu; } else { - std::vector> localTransformationMatrix = getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); - return matMul(transformationMatrix, localTransformationMatrix); + std::vector> destTransformationMatrixCurr = getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); + return matMul(destTransformationMatrixCurr, currTransformationMatrixImu); } } @@ -506,25 +506,25 @@ std::vector> CalibrationHandler::computeExtrinsicMatrix(Camer transformationMatrix.push_back(homogeneous_vector); return transformationMatrix; } else { - std::vector> futureTransformationMatrix = + std::vector> destTransformationMatrixCurr = computeExtrinsicMatrix(eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket, dstCamera, useSpecTranslation); - std::vector> currTransformationMatrix = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix; + std::vector> currTransformationMatrixSrc = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix; if(useSpecTranslation) { const dai::Point3f& mTrans = eepromData.cameraData.at(srcCamera).extrinsics.specTranslation; if(mTrans.x == 0 && mTrans.y == 0 && mTrans.z == 0) { throw std::runtime_error("Cannot use useSpecTranslation argument since specTranslation has {0, 0, 0}"); } - currTransformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x); - currTransformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y); - currTransformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z); + currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x); + currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y); + currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z); } else { - currTransformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x); - currTransformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y); - currTransformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z); + currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x); + currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y); + currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z); } std::vector homogeneous_vector = {0, 0, 0, 1}; - currTransformationMatrix.push_back(homogeneous_vector); - return matMul(currTransformationMatrix, futureTransformationMatrix); + currTransformationMatrixSrc.push_back(homogeneous_vector); + return matMul(destTransformationMatrixCurr, currTransformationMatrixSrc); } } From 02b1be7b699f6f36060bd48b6adb970d212b3e22 Mon Sep 17 00:00:00 2001 From: saching13 Date: Thu, 28 Sep 2023 23:10:09 -0700 Subject: [PATCH 60/63] clang update --- src/device/CalibrationHandler.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 2291878c3..cf74c1361 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -435,7 +435,8 @@ std::vector> CalibrationHandler::getImuToCameraExtrinsics(Cam if(eepromData.imuExtrinsics.toCameraSocket == cameraId) { return currTransformationMatrixImu; } else { - std::vector> destTransformationMatrixCurr = getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); + std::vector> destTransformationMatrixCurr = + getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); return matMul(destTransformationMatrixCurr, currTransformationMatrixImu); } } From b754f590a8a8af1444701b46221a660b6d23844b Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 29 Sep 2023 14:45:59 +0200 Subject: [PATCH 61/63] [FW] deviceName fixes and updated for EepromData changes --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- examples/ColorCamera/rgb_preview.cpp | 2 +- shared/depthai-shared | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index b36d86237..8ad8d1296 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "5c8d51b3a9e7687f113beda652036043eb530506") +set(DEPTHAI_DEVICE_SIDE_COMMIT "39a9d271a9ed0172f6481877723fca96d41b54c6") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/ColorCamera/rgb_preview.cpp b/examples/ColorCamera/rgb_preview.cpp index 1151195d4..a5d2a30cc 100644 --- a/examples/ColorCamera/rgb_preview.cpp +++ b/examples/ColorCamera/rgb_preview.cpp @@ -38,7 +38,7 @@ int main() { } // Device name - cout << "Device name: " << device.getDeviceName() << endl; + cout << "Device name: " << device.getDeviceName() << " Product name: " << device.getProductName() << endl; // Output queue will be used to get the rgb frames from the output defined above auto qRgb = device.getOutputQueue("rgb", 4, false); diff --git a/shared/depthai-shared b/shared/depthai-shared index 805b62339..8bacf258a 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 805b623396f8e32b31f5bb24b5da0873597fd41b +Subproject commit 8bacf258a2ccf507634da153a7166aec77af1ea7 From 73d9bd468ee8a549d8c1a8b719a869053cc03be4 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 29 Sep 2023 19:00:27 +0200 Subject: [PATCH 62/63] Increased num XLink connections to 64 --- src/xlink/XLinkConnection.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index 3e41fac1d..61fe0c5b7 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -116,7 +116,7 @@ std::vector XLinkConnection::getAllConnectedDevices(XLinkDeviceState std::vector devices; unsigned int numdev = 0; - std::array deviceDescAll = {}; + std::array deviceDescAll = {}; deviceDesc_t suitableDevice = {}; suitableDevice.protocol = getDefaultProtocol(); suitableDevice.platform = X_LINK_ANY_PLATFORM; From ff0617ba10e91cc42272afa7bf2a4c9f289c019e Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 29 Sep 2023 19:00:37 +0200 Subject: [PATCH 63/63] Bumped num XLink connections to 64 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3a7ad0371..e678a2919 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -46,7 +46,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.22.0" LANGUAGES CXX C) +project(depthai VERSION "2.23.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)