From db02740f82c3e6ea55f728ebedf2fdf7722e9fc4 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 7 Jan 2021 06:03:40 +0200 Subject: [PATCH 01/53] ColorCamera: add `isp`, `raw` outputs --- include/depthai/pipeline/node/ColorCamera.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index ac7627ba0..5cd47e516 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -70,6 +70,8 @@ class ColorCamera : public Node { * The message is sent only when a CameraControl message arrives to inputControl with captureStill command set. */ Output still{*this, "still", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; + Output isp{*this, "isp", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; + Output raw{*this, "raw", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; /** * Specify which board socket to use @@ -218,6 +220,8 @@ class ColorCamera : public Node { * @returns Preview keep aspect ratio option */ bool getPreviewKeepAspectRatio(); + + void setEnablePreviewStillVideoStreams(bool enable); }; } // namespace node From ea9a98bd51fd1275dfd67d61353672fafb2f4ba0 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Fri, 12 Feb 2021 01:03:34 +0200 Subject: [PATCH 02/53] ColorCamera: add setIspScale/setIspScaleFull API --- include/depthai/pipeline/node/ColorCamera.hpp | 4 ++++ shared/depthai-shared | 2 +- src/pipeline/node/ColorCamera.cpp | 15 +++++++++++++++ 3 files changed, 20 insertions(+), 1 deletion(-) diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 5cd47e516..9f6baac99 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -130,6 +130,10 @@ class ColorCamera : public Node { /// Get sensor resolution Properties::SensorResolution getResolution() const; + // set 'isp' output scaling + void setIspScale(int numerator, int denominator); + void setIspScaleFull(int horizNum, int horizDenom, int vertNum, int vertDenom); + /** * Set rate at which camera should produce frames * @param fps Rate in frames per second diff --git a/shared/depthai-shared b/shared/depthai-shared index 128f377f6..bc356542a 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 128f377f678bd0ade7957741ebfe7832c58fbe39 +Subproject commit bc356542a94d7c75635630b119bd81b988747ab4 diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 2bc2ad433..f89a40b92 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -134,6 +134,21 @@ void ColorCamera::setStillSize(int width, int height) { properties.stillHeight = height; } +void ColorCamera::setIspScale(int numerator, int denominator) { + properties.ispScale.horizNumerator = numerator; + properties.ispScale.horizDenominator = denominator; + properties.ispScale.vertNumerator = numerator; + properties.ispScale.vertDenominator = denominator; +} + +void ColorCamera::setIspScaleFull(int horizNum, int horizDenom, int vertNum, int vertDenom) { + properties.ispScale.horizNumerator = horizNum; + properties.ispScale.horizDenominator = horizDenom; + properties.ispScale.vertNumerator = vertNum; + properties.ispScale.vertDenominator = vertDenom; +} + + void ColorCamera::setResolution(ColorCameraProperties::SensorResolution resolution) { properties.resolution = resolution; } From 0431b74bfaa38d5ea784fda96ec6cd0a64630462 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 9 Mar 2021 05:04:41 +0200 Subject: [PATCH 03/53] StereoDepth: deprecate setOutputDepth/Rectified --- include/depthai/pipeline/node/StereoDepth.hpp | 24 +++++++++++++++---- shared/depthai-shared | 2 +- src/pipeline/node/StereoDepth.cpp | 14 +++++++++-- 3 files changed, 33 insertions(+), 7 deletions(-) diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index c159990bb..61672b899 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -86,6 +86,20 @@ class StereoDepth : public Node { */ void setEmptyCalibration(); + /** + * Override the baseline (left-to-right camera distance) used for depth calculation. + * Could be useful in conjunction with 'setEmptyCalibration()' + * @param baseline Baseline in centimeters. Default: 0 (don't override) + */ + void setBaselineOverrideCm(float baseline); + + /** + * Override the camera horizontal FOV (field of view) used for depth calculation. + * Could be useful in conjunction with 'setEmptyCalibration()' + * @param fov Horizontal FOV in degrees. Default: 0 (don't override) + */ + void setFovOverrideDegrees(float fov); + /** * Specify input resolution size * @@ -138,15 +152,17 @@ class StereoDepth : public Node { void setRectifyMirrorFrame(bool enable); /** - * Enable outputting rectified frames. Optimizes computation on device side when disabled + * Enable outputting rectified frames. Optimizes computation on device side when disabled. + * DEPRECATED. The outputs are auto-enabled if used */ - void setOutputRectified(bool enable); + [[deprecated("Function call should be removed")]] void setOutputRectified(bool enable); /** * Enable outputting 'depth' stream (converted from disparity). - * In certain configurations, this will disable 'disparity' stream + * In certain configurations, this will disable 'disparity' stream. + * DEPRECATED. The output is auto-enabled if used */ - void setOutputDepth(bool enable); + [[deprecated("Function call should be removed")]] void setOutputDepth(bool enable); }; } // namespace node diff --git a/shared/depthai-shared b/shared/depthai-shared index bc356542a..a6eac9d87 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit bc356542a94d7c75635630b119bd81b988747ab4 +Subproject commit a6eac9d87eda4e1f7b08e7dc9c815039c93abc2e diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 9d36d260f..1b0326c40 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -3,6 +3,8 @@ // standard #include +#include "spdlog/spdlog.h" + namespace dai { namespace node { @@ -59,6 +61,12 @@ void StereoDepth::setEmptyCalibration(void) { properties.calibration = empty; } +void StereoDepth::setBaselineOverrideCm(float baseline) { + properties.baselineOverrideCm = baseline; +} +void StereoDepth::setFovOverrideDegrees(float fov) { + properties.fovOverrideDegrees = fov; +} void StereoDepth::setInputResolution(int width, int height) { properties.width = width; properties.height = height; @@ -85,10 +93,12 @@ void StereoDepth::setRectifyMirrorFrame(bool enable) { properties.rectifyMirrorFrame = enable; } void StereoDepth::setOutputRectified(bool enable) { - properties.enableOutputRectified = enable; + (void)enable; + spdlog::warn("{} is deprecated. The output is auto-enabled if used", __func__); } void StereoDepth::setOutputDepth(bool enable) { - properties.enableOutputDepth = enable; + (void)enable; + spdlog::warn("{} is deprecated. The output is auto-enabled if used", __func__); } } // namespace node From 5f2f312e9d57a65cc3c9f29a241c45725c75f05a Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 9 Mar 2021 05:12:00 +0200 Subject: [PATCH 04/53] ColorCamera: add API to get 'isp' scaled output size --- include/depthai/pipeline/node/ColorCamera.hpp | 15 ++++++++-- src/pipeline/node/ColorCamera.cpp | 28 +++++++++++++++++++ 2 files changed, 40 insertions(+), 3 deletions(-) diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 9f6baac99..df21226ee 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -25,6 +25,8 @@ class ColorCamera : public Node { std::shared_ptr rawControl; + int getScaledSize(int input, int num, int denom) const; + public: /** * Constructs ColorCamera node. @@ -130,8 +132,10 @@ class ColorCamera : public Node { /// Get sensor resolution Properties::SensorResolution getResolution() const; - // set 'isp' output scaling + /// Set 'isp' output scaling, keeping the aspect ratio void setIspScale(int numerator, int denominator); + + /// Set 'isp' output scaling, per direction (horizontal and vertical) void setIspScaleFull(int horizNum, int horizDenom, int vertNum, int vertDenom); /** @@ -174,6 +178,13 @@ class ColorCamera : public Node { /// Get sensor resolution height int getResolutionHeight() const; + /// Get 'isp' output resolution as size, after scaling + std::tuple getIspSize() const; + /// Get 'isp' output width + int getIspWidth() const; + /// Get 'isp' output height + int getIspHeight() const; + /** * Specify sensor center crop. * Resolution size / video size @@ -224,8 +235,6 @@ class ColorCamera : public Node { * @returns Preview keep aspect ratio option */ bool getPreviewKeepAspectRatio(); - - void setEnablePreviewStillVideoStreams(bool enable); }; } // namespace node diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index f89a40b92..36614b990 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -266,6 +266,34 @@ int ColorCamera::getResolutionHeight() const { return std::get<1>(getResolutionSize()); } +int ColorCamera::getScaledSize(int input, int num, int denom) const { + return (input * num - 1) / denom + 1; +} + +int ColorCamera::getIspWidth() const { + int inW = getResolutionWidth(); + int num = properties.ispScale.horizNumerator; + int den = properties.ispScale.horizDenominator; + if (num > 0 && den > 0) { + return getScaledSize(inW, num, den); + } + return inW; +} + +int ColorCamera::getIspHeight() const { + int inH = getResolutionHeight(); + int num = properties.ispScale.vertNumerator; + int den = properties.ispScale.vertDenominator; + if (num > 0 && den > 0) { + return getScaledSize(inH, num, den); + } + return inH; +} + +std::tuple ColorCamera::getIspSize() const { + return {getIspWidth(), getIspHeight()}; +} + void ColorCamera::sensorCenterCrop() { properties.sensorCropX = ColorCameraProperties::AUTO; properties.sensorCropY = ColorCameraProperties::AUTO; From e04b25773b3c369fdd59b153fd96f186741f6d58 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 9 Mar 2021 05:43:54 +0200 Subject: [PATCH 05/53] `make clangformat` --- src/opencv/ImgFrame.cpp | 2 +- src/pipeline/node/ColorCamera.cpp | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/opencv/ImgFrame.cpp b/src/opencv/ImgFrame.cpp index 31401e9a4..42c500597 100644 --- a/src/opencv/ImgFrame.cpp +++ b/src/opencv/ImgFrame.cpp @@ -64,7 +64,7 @@ cv::Mat ImgFrame::getFrame(bool deepCopy) { // Check if enough data long requiredSize = CV_ELEM_SIZE(type) * size.area(); - if((long) img.data.size() < requiredSize) { + if((long)img.data.size() < requiredSize) { throw std::runtime_error("ImgFrame doesn't have enough data to encode specified frame. Maybe metadataOnly transfer was made?"); } if(getWidth() <= 0 || getHeight() <= 0) { diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 36614b990..026714ca8 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -148,7 +148,6 @@ void ColorCamera::setIspScaleFull(int horizNum, int horizDenom, int vertNum, int properties.ispScale.vertDenominator = vertDenom; } - void ColorCamera::setResolution(ColorCameraProperties::SensorResolution resolution) { properties.resolution = resolution; } @@ -274,7 +273,7 @@ int ColorCamera::getIspWidth() const { int inW = getResolutionWidth(); int num = properties.ispScale.horizNumerator; int den = properties.ispScale.horizDenominator; - if (num > 0 && den > 0) { + if(num > 0 && den > 0) { return getScaledSize(inW, num, den); } return inW; @@ -284,7 +283,7 @@ int ColorCamera::getIspHeight() const { int inH = getResolutionHeight(); int num = properties.ispScale.vertNumerator; int den = properties.ispScale.vertDenominator; - if (num > 0 && den > 0) { + if(num > 0 && den > 0) { return getScaledSize(inH, num, den); } return inH; From 2f9ad0af32888a56b26bcaa20387df4cf25b37f1 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 9 Mar 2021 05:48:54 +0200 Subject: [PATCH 06/53] Update FW: stereo fixes, stereo/ColorCamera 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 14916809d..dcacecb9e 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 "ae1c9ddcbd69ecbf9f6aeb720f3158a3003a8b3a") +set(DEPTHAI_DEVICE_SIDE_COMMIT "665ede7a8669d441d02e4eb3be635b740d0ef190") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From f22ca12afef085464f6ab5bbe5b60b7ee3b00252 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Sat, 13 Mar 2021 02:25:57 +0200 Subject: [PATCH 07/53] Add API to configure disparity/depth alignment: left/right/center. Works with LRcheck or LRcheck+Subpixel for now. The updated FW also fixes some crashes with LRcheck mode enabled --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/node/StereoDepth.hpp | 5 +++++ shared/depthai-shared | 2 +- src/pipeline/node/StereoDepth.cpp | 5 ++++- 4 files changed, 11 insertions(+), 3 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index dcacecb9e..c3d59c87e 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 "665ede7a8669d441d02e4eb3be635b740d0ef190") +set(DEPTHAI_DEVICE_SIDE_COMMIT "0f1ac77644d6fd0ce75485e9fa20d7e34ae23ce7") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index 61672b899..fff06b8b0 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -112,6 +112,11 @@ class StereoDepth : public Node { */ void setMedianFilter(Properties::MedianFilter median); + /** + * @param align Set the disparity/depth alignment to the perspective of one camera + */ + void setDepthAlign(Properties::DepthAlign align); + /** * Confidence threshold for disparity calculation * @param confThr Confidence threshold value 0..255 diff --git a/shared/depthai-shared b/shared/depthai-shared index a6eac9d87..c2d7a82ad 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit a6eac9d87eda4e1f7b08e7dc9c815039c93abc2e +Subproject commit c2d7a82ad91647ff0a8b0c0530b6395c54e5ae79 diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 1b0326c40..86ed9a0b4 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -71,9 +71,12 @@ void StereoDepth::setInputResolution(int width, int height) { properties.width = width; properties.height = height; } -void StereoDepth::setMedianFilter(StereoDepthProperties::MedianFilter median) { +void StereoDepth::setMedianFilter(Properties::MedianFilter median) { properties.median = median; } +void StereoDepth::setDepthAlign(Properties::DepthAlign align) { + properties.depthAlign = align; +} void StereoDepth::setConfidenceThreshold(int confThr) { properties.confidenceThreshold = confThr; } From 974dc98050865488cf6b70c32eac81cfd4af5be5 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 25 Mar 2021 16:07:27 +0200 Subject: [PATCH 08/53] StereoDepth: add overloaded setDepthAlign(CameraBoardSocket) --- include/depthai/pipeline/node/StereoDepth.hpp | 8 +++++++- shared/depthai-shared | 2 +- src/pipeline/node/StereoDepth.cpp | 5 +++++ 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index f026196d9..162357948 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -113,10 +113,16 @@ class StereoDepth : public Node { void setMedianFilter(Properties::MedianFilter median); /** - * @param align Set the disparity/depth alignment to the perspective of one camera + * @param align Set the disparity/depth alignment: centered (between the 'left' and 'right' inputs), + * or from the perspective of a rectified output stream */ void setDepthAlign(Properties::DepthAlign align); + /** + * @param camera Set the camera from whose perspective the disparity/depth will be aligned + */ + void setDepthAlign(CameraBoardSocket camera); + /** * Confidence threshold for disparity calculation * @param confThr Confidence threshold value 0..255 diff --git a/shared/depthai-shared b/shared/depthai-shared index dd040cdc8..43676a0b4 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit dd040cdc8a88f2d21050d15b4f0b48371d115ba1 +Subproject commit 43676a0b470688f989971bae9648a4af2107d5f1 diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 86ed9a0b4..71692026f 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -76,6 +76,11 @@ void StereoDepth::setMedianFilter(Properties::MedianFilter median) { } void StereoDepth::setDepthAlign(Properties::DepthAlign align) { properties.depthAlign = align; + // Unset 'depthAlignCamera', that would take precedence otherwise + properties.depthAlignCamera = CameraBoardSocket::AUTO; +} +void StereoDepth::setDepthAlign(CameraBoardSocket camera) { + properties.depthAlignCamera = camera; } void StereoDepth::setConfidenceThreshold(int confThr) { properties.confidenceThreshold = confThr; From 4ec7f1fd68a648581c923cc6a9cb9b647a7e4d89 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 25 Mar 2021 16:09:16 +0200 Subject: [PATCH 09/53] StereoDepth: remove for now 'setBaselineOverrideCm', 'setFovOverrideDegrees', will be refactored when the new calibration structure is integrated --- include/depthai/pipeline/node/StereoDepth.hpp | 14 -------------- src/pipeline/node/StereoDepth.cpp | 6 ------ 2 files changed, 20 deletions(-) diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index 162357948..d1e0301e9 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -86,20 +86,6 @@ class StereoDepth : public Node { */ void setEmptyCalibration(); - /** - * Override the baseline (left-to-right camera distance) used for depth calculation. - * Could be useful in conjunction with 'setEmptyCalibration()' - * @param baseline Baseline in centimeters. Default: 0 (don't override) - */ - void setBaselineOverrideCm(float baseline); - - /** - * Override the camera horizontal FOV (field of view) used for depth calculation. - * Could be useful in conjunction with 'setEmptyCalibration()' - * @param fov Horizontal FOV in degrees. Default: 0 (don't override) - */ - void setFovOverrideDegrees(float fov); - /** * Specify input resolution size * diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 71692026f..38aa97101 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -61,12 +61,6 @@ void StereoDepth::setEmptyCalibration(void) { properties.calibration = empty; } -void StereoDepth::setBaselineOverrideCm(float baseline) { - properties.baselineOverrideCm = baseline; -} -void StereoDepth::setFovOverrideDegrees(float fov) { - properties.fovOverrideDegrees = fov; -} void StereoDepth::setInputResolution(int width, int height) { properties.width = width; properties.height = height; From cb04d52d75c63c72582ba21baef9c3cccd50c75c Mon Sep 17 00:00:00 2001 From: Dale Phurrough Date: Mon, 8 Mar 2021 19:22:33 +0100 Subject: [PATCH 10/53] fix narrowing, clangformat, mutex lock, VideoEncoder::get/setFrameRate to float --- .../depthai/pipeline/node/VideoEncoder.hpp | 4 +-- src/bspatch/bspatch.c | 4 +-- src/device/CallbackHandler.cpp | 2 +- src/device/Device.cpp | 6 ++-- src/device/DeviceBootloader.cpp | 30 +++++++++---------- src/opencv/ImgFrame.cpp | 4 +-- src/pipeline/AssetManager.cpp | 4 +-- src/pipeline/datatype/ImageManipConfig.cpp | 2 +- src/pipeline/datatype/NNData.cpp | 6 ++-- src/pipeline/datatype/StreamPacketParser.cpp | 2 +- src/pipeline/node/ColorCamera.cpp | 8 +++-- src/pipeline/node/NeuralNetwork.cpp | 2 +- src/pipeline/node/VideoEncoder.cpp | 14 ++++----- src/xlink/XLinkConnection.cpp | 6 ++-- src/xlink/XLinkStream.cpp | 12 ++++---- 15 files changed, 55 insertions(+), 51 deletions(-) mode change 100644 => 100755 src/opencv/ImgFrame.cpp mode change 100644 => 100755 src/pipeline/node/ColorCamera.cpp diff --git a/include/depthai/pipeline/node/VideoEncoder.hpp b/include/depthai/pipeline/node/VideoEncoder.hpp index e74c2f979..26560924b 100644 --- a/include/depthai/pipeline/node/VideoEncoder.hpp +++ b/include/depthai/pipeline/node/VideoEncoder.hpp @@ -101,7 +101,7 @@ class VideoEncoder : public Node { * Sets expected frame rate * @param frameRate Frame rate in frames per second */ - void setFrameRate(int frameRate); + void setFrameRate(float frameRate); /// Get rate control mode Properties::RateControlMode getRateControlMode() const; @@ -123,7 +123,7 @@ class VideoEncoder : public Node { /// Get input height int getHeight() const; /// Get frame rate - int getFrameRate() const; + float getFrameRate() const; }; } // namespace node diff --git a/src/bspatch/bspatch.c b/src/bspatch/bspatch.c index 12dda571b..628a76ab8 100644 --- a/src/bspatch/bspatch.c +++ b/src/bspatch/bspatch.c @@ -126,12 +126,12 @@ int bspatch_mem(const uint8_t* oldfile_bin, const int64_t oldfile_size, const ui uint8_t* p_decompressed_block_end[NUM_BLOCKS] = {NULL, NULL, NULL}; for(int i = 0; i < NUM_BLOCKS; i++) { - unsigned int decompressed_size = newsize * 4; + unsigned int decompressed_size = (unsigned int)newsize * 4; p_decompressed_block_original[i] = malloc(decompressed_size); // reserve enough memory int ret = 0; if((ret = BZ2_bzBuffToBuffDecompress( - (char*)p_decompressed_block_original[i], &decompressed_size, (char*)patchfile_bin + block_offset_bz2[i], block_size_bz2[i], 0, 0)) + (char*)p_decompressed_block_original[i], &decompressed_size, (char*)patchfile_bin + block_offset_bz2[i], (unsigned int)block_size_bz2[i], 0, 0)) != BZ_OK) { (void)ret; error = -1; diff --git a/src/device/CallbackHandler.cpp b/src/device/CallbackHandler.cpp index 3e0ce3a21..cf2176929 100644 --- a/src/device/CallbackHandler.cpp +++ b/src/device/CallbackHandler.cpp @@ -37,7 +37,7 @@ CallbackHandler::CallbackHandler(std::shared_ptr conn, stream.write(serialized); } - } catch(const std::exception& ex) { + } catch(const std::exception&) { // TODO(themarpe) - throw an exception assert(0 && "TODO"); } diff --git a/src/device/Device.cpp b/src/device/Device.cpp index ac4239c12..13c8008d7 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -398,7 +398,7 @@ void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, c client = std::unique_ptr>( new nanorpc::core::client([this](nanorpc::core::type::buffer request) { - std::unique_lock(this->rpcMutex); + std::unique_lock lock(this->rpcMutex); // Log the request data if(spdlog::get_level() == spdlog::level::trace) { @@ -419,7 +419,7 @@ void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, c while(watchdogRunning) { try { client->call("watchdogKeepalive"); - } catch(const std::exception& ex) { + } catch(const std::exception&) { break; } // Ping with a period half of that of the watchdog timeout @@ -564,7 +564,7 @@ void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, c }); } - } catch(const std::exception& ex) { + } catch(const std::exception&) { // close device (cleanup) close(); // Rethrow original exception diff --git a/src/device/DeviceBootloader.cpp b/src/device/DeviceBootloader.cpp index 0bedc388e..c07ebc56c 100644 --- a/src/device/DeviceBootloader.cpp +++ b/src/device/DeviceBootloader.cpp @@ -98,26 +98,26 @@ std::vector DeviceBootloader::createDepthaiApplicationPackage(Pipeline& // First section, MVCMD, name '__firmware' sbr_section_set_name(fwSection, "__firmware"); sbr_section_set_bootable(fwSection, true); - sbr_section_set_size(fwSection, deviceFirmware.size()); - sbr_section_set_checksum(fwSection, sbr_compute_checksum(deviceFirmware.data(), deviceFirmware.size())); + sbr_section_set_size(fwSection, static_cast(deviceFirmware.size())); + sbr_section_set_checksum(fwSection, sbr_compute_checksum(deviceFirmware.data(), static_cast(deviceFirmware.size()))); sbr_section_set_offset(fwSection, SBR_RAW_SIZE); // Second section, pipeline schema, name 'pipeline' sbr_section_set_name(pipelineSection, "pipeline"); - sbr_section_set_size(pipelineSection, pipelineBinary.size()); - sbr_section_set_checksum(pipelineSection, sbr_compute_checksum(pipelineBinary.data(), pipelineBinary.size())); + sbr_section_set_size(pipelineSection, static_cast(pipelineBinary.size())); + sbr_section_set_checksum(pipelineSection, sbr_compute_checksum(pipelineBinary.data(), static_cast(pipelineBinary.size()))); sbr_section_set_offset(pipelineSection, getSectionAlignedOffset(fwSection->offset + fwSection->size)); // Third section, assets map, name 'assets' sbr_section_set_name(assetsSection, "assets"); - sbr_section_set_size(assetsSection, assetsBinary.size()); - sbr_section_set_checksum(assetsSection, sbr_compute_checksum(assetsBinary.data(), assetsBinary.size())); + sbr_section_set_size(assetsSection, static_cast(assetsBinary.size())); + sbr_section_set_checksum(assetsSection, sbr_compute_checksum(assetsBinary.data(), static_cast(assetsBinary.size()))); sbr_section_set_offset(assetsSection, getSectionAlignedOffset(pipelineSection->offset + pipelineSection->size)); // Fourth section, asset storage, name 'asset_storage' sbr_section_set_name(assetStorageSection, "asset_storage"); - sbr_section_set_size(assetStorageSection, assetStorage.size()); - sbr_section_set_checksum(assetStorageSection, sbr_compute_checksum(assetStorage.data(), assetStorage.size())); + sbr_section_set_size(assetStorageSection, static_cast(assetStorage.size())); + sbr_section_set_checksum(assetStorageSection, sbr_compute_checksum(assetStorage.data(), static_cast(assetStorage.size()))); sbr_section_set_offset(assetStorageSection, getSectionAlignedOffset(assetsSection->offset + assetsSection->size)); // TODO(themarpe) - Add additional sections (Pipeline nodes will be able to use sections) @@ -127,7 +127,7 @@ std::vector DeviceBootloader::createDepthaiApplicationPackage(Pipeline& fwPackage.resize(lastSection->offset + lastSection->size); // Serialize SBR - sbr_serialize(&sbr, fwPackage.data(), fwPackage.size()); + sbr_serialize(&sbr, fwPackage.data(), static_cast(fwPackage.size())); // Write to fwPackage for(unsigned i = 0; i < deviceFirmware.size(); i++) fwPackage[fwSection->offset + i] = deviceFirmware[i]; @@ -187,7 +187,7 @@ void DeviceBootloader::init(bool embeddedMvcmd, const std::string& pathToMvcmd) while(watchdogRunning) { try { stream.write(watchdogKeepalive); - } catch(const std::exception& ex) { + } catch(const std::exception&) { break; } // Ping with a period half of that of the watchdog timeout @@ -199,7 +199,7 @@ void DeviceBootloader::init(bool embeddedMvcmd, const std::string& pathToMvcmd) stream.write(reset); // Dummy read (wait till link falls down) stream.readRaw(); - } catch(const std::exception& error) { + } catch(const std::exception&) { } // ignore // Sleep a bit, so device isn't available anymore @@ -284,8 +284,8 @@ std::tuple DeviceBootloader::flashDepthaiApplicationPackage(s // send request to FLASH BOOTLOADER dai::bootloader::request::UpdateFlash updateFlash; updateFlash.storage = dai::bootloader::request::UpdateFlash::SBR; - updateFlash.totalSize = package.size(); - updateFlash.numPackets = ((package.size() - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1; + updateFlash.totalSize = static_cast(package.size()); + updateFlash.numPackets = ((static_cast(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1; if(!sendBootloaderRequest(streamId, updateFlash)) return {false, "Couldn't send bootloader flash request"}; // After that send numPackets of data @@ -333,8 +333,8 @@ std::tuple DeviceBootloader::flashBootloader(std::function(package.size()); + updateFlash.numPackets = ((static_cast(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1; if(!sendBootloaderRequest(streamId, updateFlash)) return {false, "Couldn't send bootloader flash request"}; // After that send numPackets of data diff --git a/src/opencv/ImgFrame.cpp b/src/opencv/ImgFrame.cpp old mode 100644 new mode 100755 index 31401e9a4..4015cfdaf --- a/src/opencv/ImgFrame.cpp +++ b/src/opencv/ImgFrame.cpp @@ -57,14 +57,14 @@ cv::Mat ImgFrame::getFrame(bool deepCopy) { case dai::RawImgFrame::Type::BITSTREAM: default: - size = cv::Size(getData().size(), 1); + size = cv::Size(static_cast(getData().size()), 1); type = CV_8UC1; break; } // Check if enough data long requiredSize = CV_ELEM_SIZE(type) * size.area(); - if((long) img.data.size() < requiredSize) { + if((long)img.data.size() < requiredSize) { throw std::runtime_error("ImgFrame doesn't have enough data to encode specified frame. Maybe metadataOnly transfer was made?"); } if(getWidth() <= 0 || getHeight() <= 0) { diff --git a/src/pipeline/AssetManager.cpp b/src/pipeline/AssetManager.cpp index 3dc49861a..3ce37caef 100644 --- a/src/pipeline/AssetManager.cpp +++ b/src/pipeline/AssetManager.cpp @@ -81,7 +81,7 @@ void AssetManager::serialize(Assets& serAssets, std::vector& asset } // calculate offset - std::uint32_t offset = storage.size() + toAdd; + std::uint32_t offset = static_cast(storage.size()) + toAdd; // Add alignment bytes storage.resize(storage.size() + toAdd); @@ -90,7 +90,7 @@ void AssetManager::serialize(Assets& serAssets, std::vector& asset storage.insert(storage.end(), a.data.begin(), a.data.end()); // Add to map the currently added asset - mutableAssets.set(a.key, offset, a.data.size(), a.alignment); + mutableAssets.set(a.key, offset, static_cast(a.data.size()), a.alignment); } assetStorage = std::move(storage); diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index b87bf74ee..dcfa18292 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -87,7 +87,7 @@ void ImageManipConfig::setRotationDegrees(float deg) { } void ImageManipConfig::setRotationRadians(float rad) { - static constexpr float rad2degFactor = 180 / M_PI; + static constexpr float rad2degFactor = static_cast(180 / M_PI); setRotationDegrees(rad * rad2degFactor); } diff --git a/src/pipeline/datatype/NNData.cpp b/src/pipeline/datatype/NNData.cpp index e2cb61cfd..458bd4aec 100644 --- a/src/pipeline/datatype/NNData.cpp +++ b/src/pipeline/datatype/NNData.cpp @@ -61,7 +61,7 @@ std::shared_ptr NNData::serialize() const { info.dataType = dataType; info.numDimensions = 0; info.name = kv.first; - info.offset = offset; + info.offset = static_cast(offset); rawNn.tensors.push_back(info); } @@ -88,7 +88,7 @@ std::shared_ptr NNData::serialize() const { info.dataType = dataType; info.numDimensions = 0; info.name = kv.first; - info.offset = offset; + info.offset = static_cast(offset); rawNn.tensors.push_back(info); } @@ -117,7 +117,7 @@ void NNData::setLayer(const std::string& name, std::vector data) { void NNData::setLayer(const std::string& name, std::vector data) { fp16Data[name] = std::vector(data.size()); for(unsigned i = 0; i < data.size(); i++) { - fp16Data[name][i] = fp16_ieee_from_fp32_value(data[i]); + fp16Data[name][i] = fp16_ieee_from_fp32_value(static_cast(data[i])); } } diff --git a/src/pipeline/datatype/StreamPacketParser.cpp b/src/pipeline/datatype/StreamPacketParser.cpp index 0a937d91b..f271242cc 100644 --- a/src/pipeline/datatype/StreamPacketParser.cpp +++ b/src/pipeline/datatype/StreamPacketParser.cpp @@ -165,7 +165,7 @@ std::vector serializeData(const std::shared_ptr& data) std::vector metadata; DatatypeEnum datatype; data->serialize(metadata, datatype); - uint32_t metadataSize = metadata.size(); + uint32_t metadataSize = static_cast(metadata.size()); // 4B datatype & 4B metadata size std::uint8_t leDatatype[4]; diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp old mode 100644 new mode 100755 index 2bc2ad433..2d91b1607 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -1,5 +1,9 @@ +// First, as other headers may include +#define _USE_MATH_DEFINES #include "depthai/pipeline/node/ColorCamera.hpp" +#include + #include "spdlog/fmt/fmt.h" namespace dai { @@ -270,8 +274,8 @@ void ColorCamera::setSensorCrop(float x, float y) { std::tuple ColorCamera::getSensorCrop() const { // AUTO - center crop by default if(properties.sensorCropX == ColorCameraProperties::AUTO || properties.sensorCropY == ColorCameraProperties::AUTO) { - float x = ((getResolutionWidth() - getVideoWidth()) / 2) / getResolutionWidth(); - float y = ((getResolutionHeight() - getVideoHeight()) / 2) / getResolutionHeight(); + float x = std::floor(((getResolutionWidth() - getVideoWidth()) / 2.0f) / getResolutionWidth()); + float y = std::floor(((getResolutionHeight() - getVideoHeight()) / 2.0f) / getResolutionHeight()); return {x, y}; } return {properties.sensorCropX, properties.sensorCropY}; diff --git a/src/pipeline/node/NeuralNetwork.cpp b/src/pipeline/node/NeuralNetwork.cpp index 3510a6d84..e592da856 100644 --- a/src/pipeline/node/NeuralNetwork.cpp +++ b/src/pipeline/node/NeuralNetwork.cpp @@ -66,7 +66,7 @@ NeuralNetwork::BlobAssetInfo NeuralNetwork::loadBlob(const std::string& path) { // Set properties URI to asset:id/blob BlobAssetInfo blobInfo; blobInfo.uri = std::string("asset:") + assetKey; - blobInfo.size = blobAsset.data.size(); + blobInfo.size = static_cast(blobAsset.data.size()); return blobInfo; } diff --git a/src/pipeline/node/VideoEncoder.cpp b/src/pipeline/node/VideoEncoder.cpp index 53f285d75..c358601f1 100644 --- a/src/pipeline/node/VideoEncoder.cpp +++ b/src/pipeline/node/VideoEncoder.cpp @@ -89,7 +89,7 @@ void VideoEncoder::setQuality(int quality) { properties.quality = quality; } -void VideoEncoder::setFrameRate(int frameRate) { +void VideoEncoder::setFrameRate(float frameRate) { properties.frameRate = frameRate; } @@ -133,7 +133,7 @@ int VideoEncoder::getHeight() const { return std::get<1>(getSize()); } -int VideoEncoder::getFrameRate() const { +float VideoEncoder::getFrameRate() const { return properties.frameRate; } @@ -154,7 +154,7 @@ void VideoEncoder::setDefaultProfilePreset(int width, int height, float fps, Vid case VideoEncoderProperties::Profile::H264_MAIN: case VideoEncoderProperties::Profile::H265_MAIN: { // By default set keyframe frequency to equal fps - properties.keyframeFrequency = fps; + properties.keyframeFrequency = static_cast(fps); // Approximate bitrate on input w/h and fps constexpr float ESTIMATION_FPS = 30.0f; @@ -164,16 +164,16 @@ void VideoEncoder::setDefaultProfilePreset(int width, int height, float fps, Vid const int pixelArea = width * height; if(pixelArea <= 1280 * 720 * AREA_MUL) { // 720p - setBitrate((4000 * 1000 / ESTIMATION_FPS) * fps); + setBitrate(static_cast((4000 * 1000 / ESTIMATION_FPS) * fps)); } else if(pixelArea <= 1920 * 1080 * AREA_MUL) { // 1080p - setBitrate((8500 * 1000 / ESTIMATION_FPS) * fps); + setBitrate(static_cast((8500 * 1000 / ESTIMATION_FPS) * fps)); } else if(pixelArea <= 2560 * 1440 * AREA_MUL) { // 1440p - setBitrate((14000 * 1000 / ESTIMATION_FPS) * fps); + setBitrate(static_cast((14000 * 1000 / ESTIMATION_FPS) * fps)); } else { // 4K - setBitrate((20000 * 1000 / ESTIMATION_FPS) * fps); + setBitrate(static_cast((20000 * 1000 / ESTIMATION_FPS) * fps)); } } break; diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index eae0fad63..fc0465a27 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -39,7 +39,7 @@ DeviceInfo::DeviceInfo(const char* mxId) : DeviceInfo(std::string(mxId)) {} std::string DeviceInfo::getMxId() const { std::string mxId = ""; - int len = std::strlen(desc.name); + int len = static_cast(std::strlen(desc.name)); for(int i = 0; i < len; i++) { if(desc.name[i] == '-') break; mxId += desc.name[i]; @@ -89,7 +89,7 @@ std::vector XLinkConnection::getAllConnectedDevices(XLinkDeviceState suitableDevice.protocol = X_LINK_ANY_PROTOCOL; suitableDevice.platform = X_LINK_ANY_PLATFORM; - auto status = XLinkFindAllSuitableDevices(state, suitableDevice, deviceDescAll.data(), deviceDescAll.size(), &numdev); + auto status = XLinkFindAllSuitableDevices(state, suitableDevice, deviceDescAll.data(), static_cast(deviceDescAll.size()), &numdev); if(status != X_LINK_SUCCESS) throw std::runtime_error("Couldn't retrieve all connected devices"); for(unsigned i = 0; i < numdev; i++) { @@ -202,7 +202,7 @@ bool XLinkConnection::bootAvailableDevice(const deviceDesc_t& deviceToBoot, cons } bool XLinkConnection::bootAvailableDevice(const deviceDesc_t& deviceToBoot, std::vector& mvcmd) { - auto status = XLinkBootMemory(&deviceToBoot, mvcmd.data(), mvcmd.size()); + auto status = XLinkBootMemory(&deviceToBoot, mvcmd.data(), static_cast(mvcmd.size())); return status == X_LINK_SUCCESS; } diff --git a/src/xlink/XLinkStream.cpp b/src/xlink/XLinkStream.cpp index bdebd47b9..a62b37d0b 100644 --- a/src/xlink/XLinkStream.cpp +++ b/src/xlink/XLinkStream.cpp @@ -22,7 +22,7 @@ XLinkStream::XLinkStream(const XLinkConnection& conn, const std::string& name, s streamId = INVALID_STREAM_ID; for(int retryCount = 0; retryCount < STREAM_OPEN_RETRIES; retryCount++) { - streamId = XLinkOpenStream(conn.getLinkId(), streamName.c_str(), maxWriteSize); + streamId = XLinkOpenStream(conn.getLinkId(), streamName.c_str(), static_cast(maxWriteSize)); // Give some time before continuing std::this_thread::sleep_for(WAIT_FOR_STREAM_RETRY); @@ -59,7 +59,7 @@ XLinkStream::~XLinkStream() { //////////////////// void XLinkStream::write(const std::uint8_t* data, std::size_t size) { - auto status = XLinkWriteData(streamId, data, size); + auto status = XLinkWriteData(streamId, data, static_cast(size)); if(status != X_LINK_SUCCESS) { throw std::runtime_error(fmt::format("Couldn't write data to stream: '{}' ({})", streamName, XLinkConnection::convertErrorCodeToString(status))); } @@ -112,7 +112,7 @@ void XLinkStream::writeSplit(const void* d, std::size_t size, std::size_t split) XLinkError_t ret = X_LINK_SUCCESS; while(remaining > 0) { sizeToTransmit = remaining > split ? split : remaining; - ret = XLinkWriteData(streamId, data + currentOffset, sizeToTransmit); + ret = XLinkWriteData(streamId, data + currentOffset, static_cast(sizeToTransmit)); if(ret != X_LINK_SUCCESS) { throw std::runtime_error(fmt::format("Couldn't write data to stream: '{}' ({})", streamName, XLinkConnection::convertErrorCodeToString(ret))); } @@ -130,7 +130,7 @@ void XLinkStream::writeSplit(const std::vector& data, std::size_t split ////////////////////// bool XLinkStream::write(const std::uint8_t* data, std::size_t size, std::chrono::milliseconds timeout) { - auto status = XLinkWriteDataWithTimeout(streamId, data, size, timeout.count()); + auto status = XLinkWriteDataWithTimeout(streamId, data, static_cast(size), static_cast(timeout.count())); if(status == X_LINK_SUCCESS) { return true; } else if(status == X_LINK_TIMEOUT) { @@ -150,7 +150,7 @@ bool XLinkStream::write(const std::vector& data, std::chrono::mill bool XLinkStream::read(std::vector& data, std::chrono::milliseconds timeout) { streamPacketDesc_t* pPacket = nullptr; - auto status = XLinkReadDataWithTimeout(streamId, &pPacket, timeout.count()); + auto status = XLinkReadDataWithTimeout(streamId, &pPacket, static_cast(timeout.count())); if(status == X_LINK_SUCCESS) { data = std::vector(pPacket->data, pPacket->data + pPacket->length); XLinkReleaseData(streamId); @@ -164,7 +164,7 @@ bool XLinkStream::read(std::vector& data, std::chrono::millisecond } bool XLinkStream::readRaw(streamPacketDesc_t*& pPacket, std::chrono::milliseconds timeout) { - auto status = XLinkReadDataWithTimeout(streamId, &pPacket, timeout.count()); + auto status = XLinkReadDataWithTimeout(streamId, &pPacket, static_cast(timeout.count())); if(status == X_LINK_SUCCESS) { return true; } else if(status == X_LINK_TIMEOUT) { From 69726b3c37598b31faa6016e677bb904b5960d95 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 31 Mar 2021 14:08:24 +0300 Subject: [PATCH 11/53] Update FW: disparity (U8) aligning to RGB works. TODO depth and subpixel (U16) --- 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 c3d59c87e..32a58d861 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 "0f1ac77644d6fd0ce75485e9fa20d7e34ae23ce7") +set(DEPTHAI_DEVICE_SIDE_COMMIT "51da5cf23ce7f05ff8466193dbe76758c4668c69") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From f809bb604c5a731192bf21ebbc4379cd99035b96 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 31 Mar 2021 14:12:23 +0300 Subject: [PATCH 12/53] Address review comments: - add `isp` and `raw` to ColorCamera list of outputs, add docstrings - overloaded `setIspScale`, with tuple inputs as options - also overloaded `setPreviewSize`, `setVideoSize` and `setStillSize` with tuple inputs --- include/depthai/pipeline/node/ColorCamera.hpp | 41 +++++++++++++++++-- src/pipeline/node/ColorCamera.cpp | 31 ++++++++++---- 2 files changed, 62 insertions(+), 10 deletions(-) diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index df21226ee..5b5749c96 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -72,7 +72,19 @@ class ColorCamera : public Node { * The message is sent only when a CameraControl message arrives to inputControl with captureStill command set. */ Output still{*this, "still", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; + + /** + * Outputs ImgFrame message that carries YUV420 planar (I420/IYUV) frame data. + * + * Generated by the ISP engine, and the source for the 'video', 'preview' and 'still' outputs + */ Output isp{*this, "isp", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; + + /** + * Outputs ImgFrame message that carries RAW10-packed (MIPI CSI-2 format) frame data. + * + * Captured directly from the camera sensor, and the source for the 'isp' output. + */ Output raw{*this, "raw", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; /** @@ -120,23 +132,46 @@ class ColorCamera : public Node { /// Set preview output size void setPreviewSize(int width, int height); + /// Set preview output size, as a tuple + void setPreviewSize(std::tuple size); + /// Set video output size void setVideoSize(int width, int height); + /// Set video output size, as a tuple + void setVideoSize(std::tuple size); + /// Set still output size void setStillSize(int width, int height); + /// Set still output size, as a tuple + void setStillSize(std::tuple size); + /// Set sensor resolution void setResolution(Properties::SensorResolution resolution); /// Get sensor resolution Properties::SensorResolution getResolution() const; - /// Set 'isp' output scaling, keeping the aspect ratio + /** + * Set 'isp' output scaling (numerator/denominator), preserving the aspect ratio. + * @param numerator Range 1..16 + * @param denominator Range 1..63 + */ void setIspScale(int numerator, int denominator); - /// Set 'isp' output scaling, per direction (horizontal and vertical) - void setIspScaleFull(int horizNum, int horizDenom, int vertNum, int vertDenom); + /// Set 'isp' output scaling, as a tuple + void setIspScale(std::tuple scale); + + /** + * Set 'isp' output scaling, per each direction. If the horizontal scaling factor + * (horizNum/horizDen) is different than the vertical scaling factor + * (vertNum/vertDen), a distorted (stretched or squished) image is generated + */ + void setIspScale(int horizNum, int horizDenom, int vertNum, int vertDenom); + + /// Set 'isp' output scaling, per each direction, as tuples + void setIspScale(std::tuple horizScale, std::tuple vertScale); /** * Set rate at which camera should produce frames diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 026714ca8..9734dffe9 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -23,7 +23,7 @@ std::string ColorCamera::getName() const { } std::vector ColorCamera::getOutputs() { - return {video, preview, still}; + return {raw, isp, video, preview, still}; } std::vector ColorCamera::getInputs() { @@ -122,32 +122,49 @@ void ColorCamera::setPreviewSize(int width, int height) { properties.previewHeight = height; } +void ColorCamera::setPreviewSize(std::tuple size) { + setPreviewSize(std::get<0>(size), std::get<1>(size)); +} + // set video output size void ColorCamera::setVideoSize(int width, int height) { properties.videoWidth = width; properties.videoHeight = height; } +void ColorCamera::setVideoSize(std::tuple size) { + setVideoSize(std::get<0>(size), std::get<1>(size)); +} + // set still output size void ColorCamera::setStillSize(int width, int height) { properties.stillWidth = width; properties.stillHeight = height; } -void ColorCamera::setIspScale(int numerator, int denominator) { - properties.ispScale.horizNumerator = numerator; - properties.ispScale.horizDenominator = denominator; - properties.ispScale.vertNumerator = numerator; - properties.ispScale.vertDenominator = denominator; +void ColorCamera::setStillSize(std::tuple size) { + setStillSize(std::get<0>(size), std::get<1>(size)); } -void ColorCamera::setIspScaleFull(int horizNum, int horizDenom, int vertNum, int vertDenom) { +void ColorCamera::setIspScale(int horizNum, int horizDenom, int vertNum, int vertDenom) { properties.ispScale.horizNumerator = horizNum; properties.ispScale.horizDenominator = horizDenom; properties.ispScale.vertNumerator = vertNum; properties.ispScale.vertDenominator = vertDenom; } +void ColorCamera::setIspScale(int numerator, int denominator) { + setIspScale(numerator, denominator, numerator, denominator); +} + +void ColorCamera::setIspScale(std::tuple scale) { + setIspScale(std::get<0>(scale), std::get<1>(scale)); +} + +void ColorCamera::setIspScale(std::tuple horizScale, std::tuple vertScale) { + setIspScale(std::get<0>(horizScale), std::get<1>(horizScale), std::get<0>(vertScale), std::get<1>(vertScale)); +} + void ColorCamera::setResolution(ColorCameraProperties::SensorResolution resolution) { properties.resolution = resolution; } From d4338e28e2699155faad5eee8f073333568638f3 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Tue, 23 Mar 2021 03:17:12 +0200 Subject: [PATCH 13/53] CameraControl: add ranges for extra controls, remove non-implemented setNoiseReductionStrength. Updated FW: all initial controls can be applied for Mono/ColorCamera (no longer limited to focus settings for Color) --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- .../pipeline/datatype/CameraControl.hpp | 50 ++++++++----------- shared/depthai-shared | 2 +- src/pipeline/datatype/CameraControl.cpp | 18 +++---- 4 files changed, 31 insertions(+), 41 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 32a58d861..04fae56da 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 "51da5cf23ce7f05ff8466193dbe76758c4668c69") +set(DEPTHAI_DEVICE_SIDE_COMMIT "80b63be3ce97dc177df17865da85403ff08348ca") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/datatype/CameraControl.hpp b/include/depthai/pipeline/datatype/CameraControl.hpp index 344b9f119..c1ab698fa 100644 --- a/include/depthai/pipeline/datatype/CameraControl.hpp +++ b/include/depthai/pipeline/datatype/CameraControl.hpp @@ -105,10 +105,10 @@ class CameraControl : public Buffer { void setAutoExposureRegion(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height); /** - * Set a command to specify auto exposure compenstaion - * @param compensation Compensation value between -128..127 + * Set a command to specify auto exposure compensation + * @param compensation Compensation value between -9..9 */ - void setAutoExposureCompensation(int8_t compensation); + void setAutoExposureCompensation(int compensation); /** * Set a command to specify auto banding mode @@ -119,7 +119,7 @@ class CameraControl : public Buffer { /** * Set a command to manually specify exposure * @param exposureTimeUs Exposure time in microseconds - * @param sensitivityIso Sensitivity as ISO value + * @param sensitivityIso Sensitivity as ISO value, usual range 100..1600 */ void setManualExposure(uint32_t exposureTimeUs, uint32_t sensitivityIso); @@ -138,46 +138,40 @@ class CameraControl : public Buffer { // Other image controls /** - * Set a command to specify auto white balance lock - * @param lock Auto white balance lock mode enabled or disabled - */ - void setBrightness(uint16_t value); // TODO move to AE? - - /** - * Set a command to specify auto white balance lock - * @param lock Auto white balance lock mode enabled or disabled + * Set a command to adjust image brightness + * @param value Brightness, range -10..10 */ - void setContrast(uint16_t value); + void setBrightness(int value); /** - * Set a command to specify saturation value - * @param value Saturation + * Set a command to adjust image contrast + * @param value Contrast, range -10..10 */ - void setSaturation(uint16_t value); + void setContrast(int value); /** - * Set a command to specify sharpness value - * @param value Sharpness + * Set a command to adjust image saturation + * @param value Saturation, range -10..10 */ - void setSharpness(uint16_t value); + void setSaturation(int value); /** - * Set a command to specify noise reduction strength - * @param value Noise reduction strength + * Set a command to adjust image sharpness + * @param value Sharpness, range 0..4 */ - void setNoiseReductionStrength(uint16_t value); + void setSharpness(int value); /** - * Set a command to specify luma denoise value - * @param value Luma denoise + * Set a command to adjust luma denoise amount + * @param value Luma denoise amount, range 0..4 */ - void setLumaDenoise(uint16_t value); + void setLumaDenoise(int value); /** - * Set a command to specify chroma denoise value - * @param value Chroma denoise + * Set a command to adjust chroma denoise amount + * @param value Chroma denoise amount, range 0..4 */ - void setChromaDenoise(uint16_t value); + void setChromaDenoise(int value); /** * Set a command to specify scene mode diff --git a/shared/depthai-shared b/shared/depthai-shared index 43676a0b4..18df31032 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 43676a0b470688f989971bae9648a4af2107d5f1 +Subproject commit 18df31032aa33e36522453d5a5b81d84ccd2242f diff --git a/src/pipeline/datatype/CameraControl.cpp b/src/pipeline/datatype/CameraControl.cpp index d58c52ba5..a95ffed17 100644 --- a/src/pipeline/datatype/CameraControl.cpp +++ b/src/pipeline/datatype/CameraControl.cpp @@ -61,7 +61,7 @@ void CameraControl::setAutoExposureRegion(uint16_t startX, uint16_t startY, uint cfg.aeRegion.height = height; cfg.aeRegion.priority = 1; // TODO } -void CameraControl::setAutoExposureCompensation(int8_t compensation) { +void CameraControl::setAutoExposureCompensation(int compensation) { cfg.setCommand(RawCameraControl::Command::EXPOSURE_COMPENSATION); cfg.expCompensation = compensation; } @@ -87,31 +87,27 @@ void CameraControl::setAutoWhiteBalanceLock(bool lock) { } // Other image controls -void CameraControl::setBrightness(uint16_t value) { +void CameraControl::setBrightness(int value) { cfg.setCommand(RawCameraControl::Command::BRIGHTNESS); cfg.brightness = value; } -void CameraControl::setContrast(uint16_t value) { +void CameraControl::setContrast(int value) { cfg.setCommand(RawCameraControl::Command::CONTRAST); cfg.contrast = value; } -void CameraControl::setSaturation(uint16_t value) { +void CameraControl::setSaturation(int value) { cfg.setCommand(RawCameraControl::Command::SATURATION); cfg.saturation = value; } -void CameraControl::setSharpness(uint16_t value) { +void CameraControl::setSharpness(int value) { cfg.setCommand(RawCameraControl::Command::SHARPNESS); cfg.sharpness = value; } -void CameraControl::setNoiseReductionStrength(uint16_t value) { - cfg.setCommand(RawCameraControl::Command::NOISE_REDUCTION_STRENGTH); - cfg.noiseReductionStrength = value; -} -void CameraControl::setLumaDenoise(uint16_t value) { +void CameraControl::setLumaDenoise(int value) { cfg.setCommand(RawCameraControl::Command::LUMA_DENOISE); cfg.lumaDenoise = value; } -void CameraControl::setChromaDenoise(uint16_t value) { +void CameraControl::setChromaDenoise(int value) { cfg.setCommand(RawCameraControl::Command::CHROMA_DENOISE); cfg.chromaDenoise = value; } From 8c3a8e6b102b51d1d34282d4d632edc6514a0669 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 16:59:53 +0300 Subject: [PATCH 14/53] Add rgb_depth_aligned example --- examples/CMakeLists.txt | 3 + examples/src/rgb_depth_aligned_example.cpp | 110 +++++++++++++++++++++ 2 files changed, 113 insertions(+) create mode 100644 examples/src/rgb_depth_aligned_example.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index a84722bb8..2190d04c5 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -130,6 +130,9 @@ dai_add_example(device_queue_event src/device_queue_event_example.cpp) # OpenCV support example dai_add_example(opencv_support src/opencv_support_example.cpp) +# RGB-depth alignment example +dai_add_example(rgb_depth_aligned src/rgb_depth_aligned_example.cpp) + # Device side decoding example for mobilenet-ssd dai_add_example(mobilenet_device_side_decoding src/mobilenet_device_side_decoding_example.cpp) target_compile_definitions(mobilenet_device_side_decoding PRIVATE BLOB_PATH="${mobilenet_blob}") diff --git a/examples/src/rgb_depth_aligned_example.cpp b/examples/src/rgb_depth_aligned_example.cpp new file mode 100644 index 000000000..76cfb496c --- /dev/null +++ b/examples/src/rgb_depth_aligned_example.cpp @@ -0,0 +1,110 @@ +#include +#include + +#include "utility.hpp" + +// Includes common necessary includes for development using depthai library +#include "depthai/depthai.hpp" + +// Optional. If set (true), the ColorCamera is downscaled from 1080p to 720p. +// Otherwise (false), the aligned depth is automatically upscaled to 1080p +static constexpr bool downscaleColor = true; + +int main() { + using namespace std; + + dai::Pipeline p; + std::vector queueNames; + + auto cam = p.create(); + cam->setBoardSocket(dai::CameraBoardSocket::RGB); + cam->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); + if(downscaleColor) cam->setIspScale(2, 3); + // For now, RGB needs fixed focus to properly align with depth. + // This value was used during calibration + cam->initialControl.setManualFocus(130); + + auto rgbOut = p.create(); + rgbOut->setStreamName("rgb"); + queueNames.push_back("rgb"); + cam->isp.link(rgbOut->input); + + auto left = p.create(); + left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); + left->setBoardSocket(dai::CameraBoardSocket::LEFT); + + auto right = p.create(); + right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); + right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + + auto stereo = p.create(); + stereo->setConfidenceThreshold(200); + // LR-check is required for depth alignment + stereo->setLeftRightCheck(true); + stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + left->out.link(stereo->left); + right->out.link(stereo->right); + + auto depthOut = p.create(); + depthOut->setStreamName("depth"); + queueNames.push_back("depth"); + // Currently we use the 'disparity' output. TODO 'depth' + stereo->disparity.link(depthOut->input); + + // Connect to device + dai::Device d(p); + d.startPipeline(); + + // Sets queues size and behavior + for(const auto& name : queueNames) { + d.getOutputQueue(name, 4, false); + } + + std::unordered_map frame; + + while(1) { + std::unordered_map> latestPacket; + + auto queueEvents = d.getQueueEvents(queueNames); + for(const auto& name : queueEvents) { + auto packets = d.getOutputQueue(name)->tryGetAll(); + auto count = packets.size(); + if(count > 0) { + latestPacket[name] = packets[count - 1]; + } + } + + for(const auto& name : queueNames) { + if(latestPacket.find(name) != latestPacket.end()) { + if(name == "depth") { + frame[name] = latestPacket[name]->getFrame(); + // Optional, extend range 0..95 -> 0..255, for a better visualisation + if(1) frame[name].convertTo(frame[name], CV_8UC1, 255. / 95); + // Optional, apply false colorization + if(1) cv::applyColorMap(frame[name], frame[name], cv::COLORMAP_HOT); + } else { + frame[name] = latestPacket[name]->getCvFrame(); + } + + cv::imshow(name, frame[name]); + } + } + + // Blend when both received + if(frame.find("rgb") != frame.end() && frame.find("depth") != frame.end()) { + // Need to have both frames in BGR format before blending + if(frame["depth"].channels() < 3) { + cv::cvtColor(frame["depth"], frame["depth"], cv::COLOR_GRAY2BGR); + } + cv::Mat blended; + cv::addWeighted(frame["rgb"], 0.6, frame["depth"], 0.4, 0, blended); + cv::imshow("rgb-depth", blended); + frame.clear(); + } + + int key = cv::waitKey(1); + if(key == 'q') { + return 0; + } + } +} From 29ca1c5a11d8a72135e1510c466a6b54c7bc150d Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 17:07:54 +0300 Subject: [PATCH 15/53] Fix conversion of YUV420p frames to OpenCV BGR, the chroma planes were swapped --- src/opencv/ImgFrame.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/opencv/ImgFrame.cpp b/src/opencv/ImgFrame.cpp index 04ac0e5da..8179b3d12 100644 --- a/src/opencv/ImgFrame.cpp +++ b/src/opencv/ImgFrame.cpp @@ -118,7 +118,7 @@ cv::Mat ImgFrame::getCvFrame() { } break; case Type::YUV420p: - cv::cvtColor(frame, output, cv::ColorConversionCodes::COLOR_YUV420p2BGR); + cv::cvtColor(frame, output, cv::ColorConversionCodes::COLOR_YUV2BGR_IYUV); break; case Type::NV12: From 3964a7ec0036c28d98d0f2532e68dedd5ba1d22c Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 19:06:50 +0300 Subject: [PATCH 16/53] Examples: remove deprecated API setOutputDepth/Rectified --- examples/src/spatial_location_calculator_example.cpp | 2 -- examples/src/spatial_mobilenet_example.cpp | 3 +-- examples/src/spatial_mobilenet_mono_example.cpp | 4 +--- examples/src/spatial_tiny_yolo_example.cpp | 3 +-- examples/src/stereo_example.cpp | 2 -- 5 files changed, 3 insertions(+), 11 deletions(-) diff --git a/examples/src/spatial_location_calculator_example.cpp b/examples/src/spatial_location_calculator_example.cpp index d0762ed75..49d487944 100644 --- a/examples/src/spatial_location_calculator_example.cpp +++ b/examples/src/spatial_location_calculator_example.cpp @@ -41,8 +41,6 @@ int main() { bool subpixel = false; // StereoDepth - stereo->setOutputDepth(outputDepth); - stereo->setOutputRectified(outputRectified); stereo->setConfidenceThreshold(255); // stereo->setMedianFilter(dai::StereoDepthProperties::MedianFilter::MEDIAN_OFF); diff --git a/examples/src/spatial_mobilenet_example.cpp b/examples/src/spatial_mobilenet_example.cpp index bef9343e1..00a2092e8 100644 --- a/examples/src/spatial_mobilenet_example.cpp +++ b/examples/src/spatial_mobilenet_example.cpp @@ -45,7 +45,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) { monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); /// setting node configs - stereo->setOutputDepth(true); stereo->setConfidenceThreshold(255); spatialDetectionNetwork->setBlobPath(nnPath); @@ -189,4 +188,4 @@ int main(int argc, char** argv) { } return 0; -} \ No newline at end of file +} diff --git a/examples/src/spatial_mobilenet_mono_example.cpp b/examples/src/spatial_mobilenet_mono_example.cpp index 17335981e..3f6ccf3ab 100644 --- a/examples/src/spatial_mobilenet_mono_example.cpp +++ b/examples/src/spatial_mobilenet_mono_example.cpp @@ -43,8 +43,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) { monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); // StereoDepth - stereo->setOutputDepth(true); - stereo->setOutputRectified(true); stereo->setConfidenceThreshold(255); // Link plugins CAM -> STEREO -> XLINK @@ -199,4 +197,4 @@ int main(int argc, char** argv) { } return 0; -} \ No newline at end of file +} diff --git a/examples/src/spatial_tiny_yolo_example.cpp b/examples/src/spatial_tiny_yolo_example.cpp index 3b85a4f66..47a839b99 100644 --- a/examples/src/spatial_tiny_yolo_example.cpp +++ b/examples/src/spatial_tiny_yolo_example.cpp @@ -52,7 +52,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) { monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); /// setting node configs - stereo->setOutputDepth(true); stereo->setConfidenceThreshold(255); spatialDetectionNetwork->setBlobPath(nnPath); @@ -203,4 +202,4 @@ int main(int argc, char** argv) { } return 0; -} \ No newline at end of file +} diff --git a/examples/src/stereo_example.cpp b/examples/src/stereo_example.cpp index c31e87341..3aaac0da4 100644 --- a/examples/src/stereo_example.cpp +++ b/examples/src/stereo_example.cpp @@ -56,8 +56,6 @@ int main() { if(withDepth) { // StereoDepth - stereo->setOutputDepth(outputDepth); - stereo->setOutputRectified(outputRectified); stereo->setConfidenceThreshold(200); stereo->setRectifyEdgeFillColor(0); // black, to better see the cutout // stereo->loadCalibrationFile("../../../../depthai/resources/depthai.calib"); From fefb4b0e870b7c61e0e62518395baf5d0b63502e Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 19:11:19 +0300 Subject: [PATCH 17/53] GitHub CI: limit cmake --parallel to 8 threads, to prevent an out-of-memory situation due to too many threads created --- .github/workflows/main.workflow.yml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/main.workflow.yml b/.github/workflows/main.workflow.yml index a015afbac..f5d32de44 100644 --- a/.github/workflows/main.workflow.yml +++ b/.github/workflows/main.workflow.yml @@ -57,7 +57,7 @@ jobs: run: cmake . -Bbuild -DDEPTHAI_CLANG_TIDY=ON -DCLANG_TIDY_BIN=clang-tidy-10 - name: Run clang-tidy - run: cmake --build build --parallel + run: cmake --build build --parallel 8 build: @@ -105,7 +105,7 @@ jobs: run: cmake -S . -B build -D DEPTHAI_BUILD_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON - name: build - run: cmake --build build --parallel + run: cmake --build build --parallel 8 integration: runs-on: ${{ matrix.os }} @@ -162,26 +162,26 @@ jobs: run: echo "$GITHUB_WORKSPACE/depthai_install/bin/" | Out-File -FilePath $env:GITHUB_PATH -Encoding utf8 -Append - name: Build and install - run: cmake --build build --config ${{ matrix.build-type }} --target install --parallel + run: cmake --build build --config ${{ matrix.build-type }} --target install --parallel 8 - name: Build and test add_subdirectory run: | cmake -S tests/integration/ -B tests/integration/build_add_subdirectory -D TEST_FIND_PACKAGE=OFF - cmake --build tests/integration/build_add_subdirectory --config ${{ matrix.build-type }} --parallel + cmake --build tests/integration/build_add_subdirectory --config ${{ matrix.build-type }} --parallel 8 cd tests/integration/build_add_subdirectory ctest -C ${{ matrix.build-type }} - name: Build and test find_package (installed) run: | cmake -S tests/integration/ -B tests/integration/build_find_package -D TEST_FIND_PACKAGE=ON -D depthai_DIR=$GITHUB_WORKSPACE/depthai_install/lib/cmake/depthai - cmake --build tests/integration/build_find_package --config ${{ matrix.build-type }} --parallel + cmake --build tests/integration/build_find_package --config ${{ matrix.build-type }} --parallel 8 cd tests/integration/build_find_package ctest -C ${{ matrix.build-type }} - name: Build and test find_package (build directory) run: | cmake -S tests/integration/ -B tests/integration/build_find_package_2 -D TEST_FIND_PACKAGE=ON -D depthai_DIR=$GITHUB_WORKSPACE/build - cmake --build tests/integration/build_find_package_2 --config ${{ matrix.build-type }} --parallel + cmake --build tests/integration/build_find_package_2 --config ${{ matrix.build-type }} --parallel 8 cd tests/integration/build_find_package_2 ctest -C ${{ matrix.build-type }} From 878e4a6611efb35a3eb70298d1d2330d6ae27014 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 19:12:43 +0300 Subject: [PATCH 18/53] README build snippets: limit `cmake --parallel` to 8 --- README.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 834410559..20a494eb8 100644 --- a/README.md +++ b/README.md @@ -48,22 +48,22 @@ git submodule update --init --recursive ``` mkdir build && cd build cmake .. -cmake --build . --parallel +cmake --build . --parallel 8 ``` **Dynamic library** ``` mkdir build && cd build cmake .. -D BUILD_SHARED_LIBS=ON -cmake --build . --parallel +cmake --build . --parallel 8 ``` ## Installing To install specify optional prefix and build target install ``` cmake .. -D CMAKE_INSTALL_PREFIX=[path/to/install/dir] -cmake --build . --parallel -cmake --build . --target install --parallel +cmake --build . --parallel 8 +cmake --build . --target install --parallel 8 ``` ## Running tests @@ -72,7 +72,7 @@ To run the tests build the library with the following options ``` mkdir build_tests && cd build_tests cmake .. -D DEPTHAI_TEST_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON -D DEPTHAI_BUILD_EXAMPLES=ON -cmake --build . --parallel +cmake --build . --parallel 8 ctest ``` From b72bb07cf1842c323843a489dbbc36c50dd0db8b Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Thu, 1 Apr 2021 19:26:02 +0300 Subject: [PATCH 19/53] Cleanup, remove some unused variables --- examples/src/spatial_location_calculator_example.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/examples/src/spatial_location_calculator_example.cpp b/examples/src/spatial_location_calculator_example.cpp index 49d487944..294c33d93 100644 --- a/examples/src/spatial_location_calculator_example.cpp +++ b/examples/src/spatial_location_calculator_example.cpp @@ -35,8 +35,6 @@ int main() { monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); - bool outputDepth = true; - bool outputRectified = false; bool lrcheck = false; bool subpixel = false; From 7df740240dac46d3c16187df8365040190eafc36 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Fri, 2 Apr 2021 04:09:44 +0300 Subject: [PATCH 20/53] Update FW: optimize depth align, make it work with subpixel/U16 (still not optimized) --- 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 04fae56da..5f9c06a5e 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 "80b63be3ce97dc177df17865da85403ff08348ca") +set(DEPTHAI_DEVICE_SIDE_COMMIT "3c19d5edec86d1b7709e5a4224a9019f5e695d32") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 1e50f3bda3c12423e3c30be38c2c9f78ea998e53 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 13 Apr 2021 12:27:14 +0200 Subject: [PATCH 21/53] Added default CMAKE_BUILD_TYPE --- CMakeLists.txt | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3d7d9295a..1ae5dff8d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -32,6 +32,18 @@ if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) endif() +# Set default build type depending on context +set(default_build_type "Release") +if(EXISTS "${CMAKE_SOURCE_DIR}/.git" AND NOT DEFINED ENV{CI}) + set(default_build_type "Debug") +endif() +if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) + message(STATUS "Setting build type to '${default_build_type}' as none was specified.") + set(CMAKE_BUILD_TYPE "${default_build_type}" CACHE STRING "Choose the type of build." FORCE) + # Set the possible values of build type for cmake-gui + set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release" "MinSizeRel" "RelWithDebInfo") +endif() + # Set default installation directory if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) set(CMAKE_INSTALL_PREFIX "${CMAKE_BINARY_DIR}/install" CACHE PATH "Installation Directory" FORCE) From 74103dee4f9c738e9f69a3c7d431c9612b92b599 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Tue, 13 Apr 2021 23:12:19 +0300 Subject: [PATCH 22/53] Fix wrongly set bitrate --- src/pipeline/node/VideoEncoder.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/pipeline/node/VideoEncoder.cpp b/src/pipeline/node/VideoEncoder.cpp index f4a1afb1f..c3e1ed947 100644 --- a/src/pipeline/node/VideoEncoder.cpp +++ b/src/pipeline/node/VideoEncoder.cpp @@ -176,16 +176,16 @@ void VideoEncoder::setDefaultProfilePreset(int width, int height, float fps, Vid const int pixelArea = width * height; if(pixelArea <= 1280 * 720 * AREA_MUL) { // 720p - setBitrateKbps(static_cast((4000 * 1000 / ESTIMATION_FPS) * fps)); + setBitrateKbps(static_cast((4000 / ESTIMATION_FPS) * fps)); } else if(pixelArea <= 1920 * 1080 * AREA_MUL) { // 1080p - setBitrateKbps(static_cast((8500 * 1000 / ESTIMATION_FPS) * fps)); + setBitrateKbps(static_cast((8500 / ESTIMATION_FPS) * fps)); } else if(pixelArea <= 2560 * 1440 * AREA_MUL) { // 1440p - setBitrateKbps(static_cast((14000 * 1000 / ESTIMATION_FPS) * fps)); + setBitrateKbps(static_cast((14000 / ESTIMATION_FPS) * fps)); } else { // 4K - setBitrateKbps(static_cast((20000 * 1000 / ESTIMATION_FPS) * fps)); + setBitrateKbps(static_cast((20000 / ESTIMATION_FPS) * fps)); } } break; From f92242f8e79e6f4e4f9cda9acb1aac7b2d268bb1 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 16 Apr 2021 11:09:57 +0200 Subject: [PATCH 23/53] Updated FW - MobileNet parsing bugfix --- 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 bc73da05b..766282761 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 "595330292c4bd1955e4e8046b0f42af2dba4b124") +set(DEPTHAI_DEVICE_SIDE_COMMIT "f34e1ec1450b659bd8ff8383eaff5b7f988cb6fc") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 676e77cca2429e361be2b65f509c59397e02e2f0 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Fri, 16 Apr 2021 18:59:46 +0300 Subject: [PATCH 24/53] Update FW: hotfix for stereo confidence threshold setting, it was overwritten to 200 --- 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 766282761..11ef95434 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 "f34e1ec1450b659bd8ff8383eaff5b7f988cb6fc") +set(DEPTHAI_DEVICE_SIDE_COMMIT "b71584129b101b30e4632678c19d33b020c04c36") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From 98a4a46ecc3b25ca47adf620276b877c90c6d4f3 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sat, 17 Apr 2021 00:14:51 +0200 Subject: [PATCH 25/53] Added nullptr check to DataInputQueue::send --- src/device/DataQueue.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/device/DataQueue.cpp b/src/device/DataQueue.cpp index daca2fa46..592236b1d 100644 --- a/src/device/DataQueue.cpp +++ b/src/device/DataQueue.cpp @@ -248,6 +248,7 @@ std::string DataInputQueue::getName() const { void DataInputQueue::send(const std::shared_ptr& rawMsg) { if(!running) throw std::runtime_error(exceptionMessage.c_str()); + if(!rawMsg) throw std::invalid_argument("Message passed is not valid (nullptr)"); // Check if stream receiver has enough space for this message if(rawMsg->data.size() > maxDataSize) { @@ -257,6 +258,7 @@ void DataInputQueue::send(const std::shared_ptr& rawMsg) { queue.push(rawMsg); } void DataInputQueue::send(const std::shared_ptr& msg) { + if(!msg) throw std::invalid_argument("Message passed is not valid (nullptr)"); send(msg->serialize()); } @@ -266,6 +268,7 @@ void DataInputQueue::send(const ADatatype& msg) { bool DataInputQueue::send(const std::shared_ptr& rawMsg, std::chrono::milliseconds timeout) { if(!running) throw std::runtime_error(exceptionMessage.c_str()); + if(!rawMsg) throw std::invalid_argument("Message passed is not valid (nullptr)"); // Check if stream receiver has enough space for this message if(rawMsg->data.size() > maxDataSize) { @@ -276,6 +279,7 @@ bool DataInputQueue::send(const std::shared_ptr& rawMsg, std::chrono: } bool DataInputQueue::send(const std::shared_ptr& msg, std::chrono::milliseconds timeout) { + if(!msg) throw std::invalid_argument("Message passed is not valid (nullptr)"); return send(msg->serialize(), timeout); } From b0dd5d6050a4e631bc863459ee360b44fe6cf7c0 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 21 Apr 2021 14:22:34 +0300 Subject: [PATCH 26/53] stereo_example: rectified flip no longer needed with LR-check on, don't link depth in pipeline if not used, and other cleanup. Update FW: ispScale factors simplification done on device, other bugfixes --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- examples/src/stereo_example.cpp | 20 +++++-------------- include/depthai/pipeline/node/ColorCamera.hpp | 5 +++-- shared/depthai-shared | 2 +- 4 files changed, 10 insertions(+), 19 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 09e2ecfd4..97fa03734 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 "3c19d5edec86d1b7709e5a4224a9019f5e695d32") +set(DEPTHAI_DEVICE_SIDE_COMMIT "c03b9979b83941cdc9feb1a29f5a1452234a65f9") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/src/stereo_example.cpp b/examples/src/stereo_example.cpp index a6916a9ee..262cef977 100644 --- a/examples/src/stereo_example.cpp +++ b/examples/src/stereo_example.cpp @@ -77,7 +77,9 @@ int main() { stereo->rectifiedRight.link(xoutRectifR->input); } stereo->disparity.link(xoutDisp->input); - stereo->depth.link(xoutDepth->input); + if (outputDepth) { + stereo->depth.link(xoutDepth->input); + } } else { // Link plugins CAM -> XLINK @@ -97,15 +99,10 @@ int main() { auto rectifRightQueue = withDepth ? d.getOutputQueue("rectified_right", 8, false) : nullptr; while(1) { - auto t1 = steady_clock::now(); auto left = leftQueue->get(); - auto t2 = steady_clock::now(); cv::imshow("left", cv::Mat(left->getHeight(), left->getWidth(), CV_8UC1, left->getData().data())); - auto t3 = steady_clock::now(); auto right = rightQueue->get(); - auto t4 = steady_clock::now(); cv::imshow("right", cv::Mat(right->getHeight(), right->getWidth(), CV_8UC1, right->getData().data())); - auto t5 = steady_clock::now(); if(withDepth) { // Note: in some configurations (if depth is enabled), disparity may output garbage data @@ -125,24 +122,17 @@ int main() { if(outputRectified) { auto rectifL = rectifLeftQueue->get(); cv::Mat rectifiedLeftFrame = rectifL->getFrame(); - cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); + //cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); cv::imshow("rectified_left", rectifiedLeftFrame); auto rectifR = rectifRightQueue->get(); cv::Mat rectifiedRightFrame = rectifR->getFrame(); - cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); + //cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); cv::imshow("rectified_right", rectifiedRightFrame); } } - int ms1 = std::chrono::duration_cast(t2 - t1).count(); - int ms2 = std::chrono::duration_cast(t3 - t2).count(); - int ms3 = std::chrono::duration_cast(t4 - t3).count(); - int ms4 = std::chrono::duration_cast(t5 - t4).count(); - int loop = std::chrono::duration_cast(t5 - t1).count(); - - std::cout << ms1 << " " << ms2 << " " << ms3 << " " << ms4 << " loop: " << loop << std::endl; int key = cv::waitKey(1); if(key == 'q') { return 0; diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 71af57342..b59ec0322 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -158,8 +158,9 @@ class ColorCamera : public Node { /** * Set 'isp' output scaling (numerator/denominator), preserving the aspect ratio. - * @param numerator Range 1..16 - * @param denominator Range 1..63 + * The fraction numerator/denominator is simplified first to a irreducible form, + * then a set of hardware scaler constraints applies: + * max numerator = 16, max denominator = 63 */ void setIspScale(int numerator, int denominator); diff --git a/shared/depthai-shared b/shared/depthai-shared index 9854618af..cf82fb1d8 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 9854618af8302858455a98929b02f4526c4eb102 +Subproject commit cf82fb1d879a32878f65d15359a5560bf6833470 From 6e11c1ff1db77d87599026acf026ba076ebd9a0a Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 21 Apr 2021 14:23:11 +0300 Subject: [PATCH 27/53] spatial_object_tracker example: remove deprecated setOutputDepth --- examples/src/spatial_object_tracker_example.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/examples/src/spatial_object_tracker_example.cpp b/examples/src/spatial_object_tracker_example.cpp index 2692e2809..317330973 100644 --- a/examples/src/spatial_object_tracker_example.cpp +++ b/examples/src/spatial_object_tracker_example.cpp @@ -42,7 +42,6 @@ dai::Pipeline createNNPipeline(std::string nnPath) { monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); /// setting node configs - stereo->setOutputDepth(true); stereo->setConfidenceThreshold(255); spatialDetectionNetwork->setBlobPath(nnPath); @@ -168,4 +167,4 @@ int main(int argc, char** argv) { } return 0; -} \ No newline at end of file +} From 308be5429de80cd9433289b2ab5c6f349a7d75e6 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Thu, 22 Apr 2021 14:00:32 +0200 Subject: [PATCH 28/53] Added capability to specify custom device binary --- src/utility/Resources.cpp | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/src/utility/Resources.cpp b/src/utility/Resources.cpp index 28693d112..140300d20 100644 --- a/src/utility/Resources.cpp +++ b/src/utility/Resources.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include #include @@ -11,6 +12,7 @@ #include "archive_entry.h" // spdlog +#include "spdlog/details/os.h" #include "spdlog/fmt/chrono.h" #include "spdlog/spdlog.h" @@ -67,6 +69,20 @@ constexpr static std::array resourcesListTarXz = { std::vector Resources::getDeviceBinary(OpenVINO::Version version, bool usb2Mode) { std::vector finalCmd; + // Check if env variable DEPTHAI_DEVICE_BINARY is set + auto fwBinaryPath = spdlog::details::os::getenv("DEPTHAI_DEVICE_BINARY"); + if(!fwBinaryPath.empty()) { + // Load binary file at path + std::ifstream stream(fwBinaryPath, std::ios::in | std::ios::binary); + if(!stream.is_open()) { + // Throw an error + // TODO(themarpe) - Unify exceptions into meaningful groups + throw std::runtime_error(fmt::format("File at path {} pointed to by DEPTHAI_DEVICE_BINARY doesn't exist.", fwBinaryPath)); + } + + return std::vector(std::istreambuf_iterator(stream), {}); + } + // Binaries are resource compiled #ifdef DEPTHAI_RESOURCE_COMPILED_BINARIES @@ -299,6 +315,9 @@ Resources::Resources() { } } r = archive_read_free(a); // Note 3 + assert(r == ARCHIVE_OK); + // Ignore 'r' variable when in Release build + (void)r; // Check that all resources were read for(const auto& cpath : resourcesListTarXz) { From 4721f1566665129853040cf97c06fddd8aeaf088 Mon Sep 17 00:00:00 2001 From: Martin Peterlin Date: Fri, 23 Apr 2021 17:39:41 +0200 Subject: [PATCH 29/53] Added a try catch for callbacks for better error messages --- src/device/DataQueue.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/device/DataQueue.cpp b/src/device/DataQueue.cpp index 592236b1d..eb648c116 100644 --- a/src/device/DataQueue.cpp +++ b/src/device/DataQueue.cpp @@ -66,7 +66,11 @@ DataOutputQueue::DataOutputQueue(const std::shared_ptr& conn, c std::unique_lock l(callbacksMtx); for(const auto& kv : callbacks) { const auto& callback = kv.second; - callback(name, data); + try { + callback(name, data); + } catch(const std::exception& ex) { + spdlog::error("Callback with id: {} throwed an exception: {}", kv.first, ex.what()); + } } } } From 1e05f8c5d14fbf43b5f641adb5974fdcaba1deea Mon Sep 17 00:00:00 2001 From: Erol444 Date: Sat, 24 Apr 2021 22:10:54 +0100 Subject: [PATCH 30/53] fixed getting size of video/still when setting isp scaling --- src/pipeline/node/ColorCamera.cpp | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 6bc3949fb..51fb4717f 100755 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -214,6 +214,19 @@ std::tuple ColorCamera::getVideoSize() const { maxVideoHeight = 2160; } + // Take into the account the ISP scaling + int numW = properties.ispScale.horizNumerator; + int denW = properties.ispScale.horizDenominator; + if(numW > 0 && denW > 0) { + maxVideoWidth = getScaledSize(maxVideoWidth, numW, denW); + } + + int numH = properties.ispScale.vertNumerator; + int denH = properties.ispScale.vertDenominator; + if(numH > 0 && denH > 0) { + maxVideoHeight = getScaledSize(maxVideoHeight, numH, denH); + } + return {maxVideoWidth, maxVideoHeight}; } @@ -242,6 +255,20 @@ std::tuple ColorCamera::getStillSize() const { maxStillWidth = 4032; // Note not 4056 as full sensor resolution maxStillHeight = 3040; } + + // Take into the account the ISP scaling + int numW = properties.ispScale.horizNumerator; + int denW = properties.ispScale.horizDenominator; + if(numW > 0 && denW > 0) { + maxStillWidth = getScaledSize(maxStillWidth, numW, denW); + } + + int numH = properties.ispScale.vertNumerator; + int denH = properties.ispScale.vertDenominator; + if(numH > 0 && denH > 0) { + maxStillHeight = getScaledSize(maxStillHeight, numH, denH); + } + return {maxStillWidth, maxStillHeight}; } From f7f856bd80899a307a9d7f4d8088df8aaa835297 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 27 Apr 2021 00:54:38 +0200 Subject: [PATCH 31/53] WIP: Decouple pipeline from Device --- include/depthai/device/Device.hpp | 76 ++++++- include/depthai/pipeline/Pipeline.hpp | 13 ++ .../pipeline/node/DetectionNetwork.hpp | 12 +- .../depthai/pipeline/node/NeuralNetwork.hpp | 9 +- .../pipeline/node/SpatialDetectionNetwork.hpp | 10 +- src/device/Device.cpp | 209 +++++++++++++----- src/pipeline/Pipeline.cpp | 27 ++- src/pipeline/node/DetectionNetwork.cpp | 12 + src/pipeline/node/SpatialDetectionNetwork.cpp | 12 + 9 files changed, 307 insertions(+), 73 deletions(-) diff --git a/include/depthai/device/Device.hpp b/include/depthai/device/Device.hpp index 2dac0ab8c..f345dc4f2 100644 --- a/include/depthai/device/Device.hpp +++ b/include/depthai/device/Device.hpp @@ -16,6 +16,7 @@ #include "depthai/xlink/XLinkStream.hpp" // shared +#include "depthai-shared/common/CameraBoardSocket.hpp" #include "depthai-shared/common/ChipTemperature.hpp" #include "depthai-shared/common/CpuUsage.hpp" #include "depthai-shared/common/MemoryInfo.hpp" @@ -140,6 +141,57 @@ class Device { */ Device(const Pipeline& pipeline, const DeviceInfo& devInfo, const std::string& pathToCmd); + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param version - OpenVINO version which the device will be booted with. Default is Pipeline::DEFAULT_OPENVINO_VERSION + */ + explicit Device(OpenVINO::Version version = Pipeline::DEFAULT_OPENVINO_VERSION); + + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param version - OpenVINO version which the device will be booted with + * @param usb2Mode - Boot device using USB2 mode firmware + */ + Device(OpenVINO::Version version, bool usb2Mode); + + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param version - OpenVINO version which the device will be booted with + * @param pathToCmd - Path to custom device firmware + */ + Device(OpenVINO::Version version, const char* pathToCmd); + + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param version - OpenVINO version which the device will be booted with + * @param pathToCmd - Path to custom device firmware + */ + Device(OpenVINO::Version version, const std::string& pathToCmd); + + /** + * Connects to device specified by devInfo. + * @param version - OpenVINO version which the device will be booted with + * @param devInfo - DeviceInfo which specifies which device to connect to + * @param usb2Mode - Boot device using USB2 mode firmware + */ + Device(OpenVINO::Version version, const DeviceInfo& devInfo, bool usb2Mode = false); + + /** + * Connects to device specified by devInfo. + * @param version - OpenVINO version which the device will be booted with + * @param devInfo - DeviceInfo which specifies which device to connect to + * @param pathToCmd - Path to custom device firmware + */ + Device(OpenVINO::Version version, const DeviceInfo& devInfo, const char* pathToCmd); + + /** + * Connects to device specified by devInfo. + * @param version - OpenVINO version which the device will be booted with + * @param devInfo - DeviceInfo which specifies which device to connect to + * @param usb2Mode - Path to custom device firmware + */ + Device(OpenVINO::Version version, const DeviceInfo& devInfo, const std::string& pathToCmd); + /** * Device destructor. Closes the connection and data queues. */ @@ -159,6 +211,14 @@ class Device { */ bool startPipeline(); + /** + * Starts the execution of a given pipeline + * @param pipeline OpenVINO version of the pipeline must match the one which the device was booted with. + * + * @return true if pipeline started, false otherwise + */ + bool startPipeline(const Pipeline& pipeline); + /** * Sets the devices logging severity level. This level affects which logs are transfered from device to host. * @@ -335,6 +395,13 @@ class Device { */ std::string getQueueEvent(std::chrono::microseconds timeout = std::chrono::microseconds(-1)); + /** + * Get cameras that are connected to the device + * + * @return Vector of connected cameras + */ + std::vector getConnectedCameras(); + /** * Retrieves current DDR memory information from device * @@ -398,7 +465,9 @@ class Device { private: // private static + void init(OpenVINO::Version version, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); void init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); + void init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); void checkClosed() const; std::shared_ptr connection; @@ -446,10 +515,9 @@ class Device { Pimpl pimpl; // Serialized pipeline - PipelineSchema schema; - Assets assets; - std::vector assetStorage; - OpenVINO::Version version; + bool hasPipeline = false; + Pipeline pipeline; + OpenVINO::Version openvinoVersion; }; } // namespace dai diff --git a/include/depthai/pipeline/Pipeline.hpp b/include/depthai/pipeline/Pipeline.hpp index 022491135..dd4d0ad11 100644 --- a/include/depthai/pipeline/Pipeline.hpp +++ b/include/depthai/pipeline/Pipeline.hpp @@ -21,6 +21,11 @@ class PipelineImpl { friend class Pipeline; friend class Node; + public: + PipelineImpl() = default; + PipelineImpl(const PipelineImpl&) = default; + + private: // static functions static bool isSamePipeline(const Node::Output& out, const Node::Input& in); static bool canConnect(const Node::Output& out, const Node::Input& in); @@ -95,6 +100,9 @@ class Pipeline { Pipeline(); explicit Pipeline(const std::shared_ptr& pimpl); + /// Clone the pipeline (Creates a copy) + Pipeline clone() const; + /// Default Pipeline openvino version constexpr static auto DEFAULT_OPENVINO_VERSION = PipelineImpl::DEFAULT_OPENVINO_VERSION; @@ -206,6 +214,11 @@ class Pipeline { void setOpenVINOVersion(OpenVINO::Version version) { impl()->forceRequiredOpenVINOVersion = version; } + + /// Get required OpenVINO version to run this pipeline + OpenVINO::Version getOpenVINOVersion() const { + return impl()->getPipelineOpenVINOVersion(); + } }; } // namespace dai diff --git a/include/depthai/pipeline/node/DetectionNetwork.hpp b/include/depthai/pipeline/node/DetectionNetwork.hpp index f495eb456..af31fe5bd 100644 --- a/include/depthai/pipeline/node/DetectionNetwork.hpp +++ b/include/depthai/pipeline/node/DetectionNetwork.hpp @@ -21,16 +21,16 @@ class DetectionNetwork : public NeuralNetwork { public: using Properties = dai::DetectionNetworkProperties; - private: std::string getName() const override; - std::vector getInputs() override; std::vector getOutputs() override; - nlohmann::json getProperties() override; + std::vector getInputs() override; protected: DetectionNetwork(const std::shared_ptr& par, int64_t nodeId); Properties properties; virtual Properties& getPropertiesRef() override; + nlohmann::json getProperties() override; + std::shared_ptr clone() override; public: /** @@ -62,6 +62,9 @@ class DetectionNetwork : public NeuralNetwork { * @brief MobileNetDetectionNetwork node. Parses MobileNet results */ class MobileNetDetectionNetwork : public DetectionNetwork { + protected: + std::shared_ptr clone() override; + public: MobileNetDetectionNetwork(const std::shared_ptr& par, int64_t nodeId); }; @@ -70,6 +73,9 @@ class MobileNetDetectionNetwork : public DetectionNetwork { * @brief YoloDetectionNetwork node. Parses Yolo results */ class YoloDetectionNetwork : public DetectionNetwork { + protected: + std::shared_ptr clone() override; + public: YoloDetectionNetwork(const std::shared_ptr& par, int64_t nodeId); diff --git a/include/depthai/pipeline/node/NeuralNetwork.hpp b/include/depthai/pipeline/node/NeuralNetwork.hpp index c7ce6aa7f..75a284be6 100644 --- a/include/depthai/pipeline/node/NeuralNetwork.hpp +++ b/include/depthai/pipeline/node/NeuralNetwork.hpp @@ -19,16 +19,17 @@ class NeuralNetwork : public Node { public: using Properties = dai::NeuralNetworkProperties; - private: - Properties properties; - std::string getName() const override; std::vector getOutputs() override; std::vector getInputs() override; + + protected: nlohmann::json getProperties() override; std::shared_ptr clone() override; tl::optional getRequiredOpenVINOVersion() override; - // void loadAssets(AssetManager& assetManager) override; + + private: + Properties properties; protected: struct BlobAssetInfo { diff --git a/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp b/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp index f52c0666e..8145f8204 100644 --- a/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp +++ b/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp @@ -21,16 +21,16 @@ class SpatialDetectionNetwork : public DetectionNetwork { public: using Properties = dai::SpatialDetectionNetworkProperties; - private: std::string getName() const override; std::vector getInputs() override; std::vector getOutputs() override; - nlohmann::json getProperties() override; protected: SpatialDetectionNetwork(const std::shared_ptr& par, int64_t nodeId); Properties properties; virtual Properties& getPropertiesRef() override; + nlohmann::json getProperties() override; + std::shared_ptr clone() override; public: /** @@ -94,6 +94,9 @@ class SpatialDetectionNetwork : public DetectionNetwork { * MobileNetSpatialDetectionNetwork. Mobilenet-SSD based network with spatial location data. */ class MobileNetSpatialDetectionNetwork : public SpatialDetectionNetwork { + protected: + std::shared_ptr clone() override; + public: MobileNetSpatialDetectionNetwork(const std::shared_ptr& par, int64_t nodeId); }; @@ -102,6 +105,9 @@ class MobileNetSpatialDetectionNetwork : public SpatialDetectionNetwork { * YoloSpatialDetectionNetwork. (tiny)Yolov3/v4 based network with spatial location data. */ class YoloSpatialDetectionNetwork : public SpatialDetectionNetwork { + protected: + std::shared_ptr clone() override; + public: YoloSpatialDetectionNetwork(const std::shared_ptr& par, int64_t nodeId); /// Set num classes diff --git a/src/device/Device.cpp b/src/device/Device.cpp index 5d260def1..d9b2de510 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -264,6 +264,60 @@ Device::Device(const Pipeline& pipeline, bool usb2Mode) { init(pipeline, true, usb2Mode, ""); } +Device::Device(OpenVINO::Version version, const DeviceInfo& devInfo, bool usb2Mode) : deviceInfo(devInfo) { + init(version, true, usb2Mode, ""); +} + +Device::Device(OpenVINO::Version version, const DeviceInfo& devInfo, const char* pathToCmd) : deviceInfo(devInfo) { + init(version, false, false, std::string(pathToCmd)); +} + +Device::Device(OpenVINO::Version version, const DeviceInfo& devInfo, const std::string& pathToCmd) : deviceInfo(devInfo) { + init(version, false, false, pathToCmd); +} + +Device::Device(OpenVINO::Version version) { + // Searches for any available device for 'default' timeout + + bool found = false; + std::tie(found, deviceInfo) = getAnyAvailableDevice(); + + // If no device found, throw + if(!found) throw std::runtime_error("No available devices"); + init(version, true, false, ""); +} + +Device::Device(OpenVINO::Version version, const char* pathToCmd) { + // Searches for any available device for 'default' timeout + + bool found = false; + std::tie(found, deviceInfo) = getAnyAvailableDevice(); + + // If no device found, throw + if(!found) throw std::runtime_error("No available devices"); + init(version, false, false, std::string(pathToCmd)); +} + +Device::Device(OpenVINO::Version version, const std::string& pathToCmd) { + // Searches for any available device for 'default' timeout + bool found = false; + std::tie(found, deviceInfo) = getAnyAvailableDevice(); + + // If no device found, throw + if(!found) throw std::runtime_error("No available devices"); + init(version, false, false, pathToCmd); +} + +Device::Device(OpenVINO::Version version, bool usb2Mode) { + // Searches for any available device for 'default' timeout + bool found = false; + std::tie(found, deviceInfo) = getAnyAvailableDevice(); + + // If no device found, throw + if(!found) throw std::runtime_error("No available devices"); + init(version, true, usb2Mode, ""); +} + void Device::close() { // Only allow to close once if(closed.exchange(true)) return; @@ -317,20 +371,39 @@ Device::~Device() { close(); } +void Device::init(OpenVINO::Version version, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd) { + // Initalize depthai library if not already + initialize(); + + // Specify the OpenVINO version + openvinoVersion = version; + hasPipeline = false; + + spdlog::debug("Device - OpenVINO version: {}", OpenVINO::getVersionName(openvinoVersion)); + + init2(embeddedMvcmd, usb2Mode, pathToMvcmd); +} + void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd) { // Initalize depthai library if not already initialize(); - // Mark the OpenVINO version and serialize the pipeline - pipeline.serialize(schema, assets, assetStorage, version); + // Mark the OpenVINO version and make a copy of the pipeline + this->pipeline = pipeline.clone(); + openvinoVersion = this->pipeline.getOpenVINOVersion(); + hasPipeline = true; + + spdlog::debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(openvinoVersion)); - spdlog::debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(version)); + init2(embeddedMvcmd, usb2Mode, pathToMvcmd); +} +void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd) { // Set logging pattern of device (device id + shared pattern) pimpl->setPattern(fmt::format("[{}] {}", deviceInfo.getMxId(), LOG_DEFAULT_PATTERN)); // Get embedded mvcmd - std::vector embeddedFw = Resources::getInstance().getDeviceFirmware(usb2Mode, version); + std::vector embeddedFw = Resources::getInstance().getDeviceFirmware(usb2Mode, openvinoVersion); // Init device (if bootloader, handle correctly - issue USB boot command) if(deviceInfo.state == X_LINK_UNBOOTED) { @@ -521,50 +594,6 @@ void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, c // Sets system inforation logging rate. By default 1s setSystemInformationLoggingRate(DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ); - // Open queues upfront, let queues know about data sizes (input queues) - // Go through Pipeline and check for 'XLinkIn' and 'XLinkOut' nodes - // and create corresponding default queues for them - for(const auto& kv : pipeline.getNodeMap()) { - const auto& node = kv.second; - const auto& xlinkIn = std::dynamic_pointer_cast(node); - if(xlinkIn == nullptr) { - continue; - } - // Create DataInputQueue's - inputQueueMap[xlinkIn->getStreamName()] = std::make_shared(connection, xlinkIn->getStreamName()); - // set max data size, for more verbosity - inputQueueMap[xlinkIn->getStreamName()]->setMaxDataSize(xlinkIn->getMaxDataSize()); - } - for(const auto& kv : pipeline.getNodeMap()) { - const auto& node = kv.second; - const auto& xlinkOut = std::dynamic_pointer_cast(node); - if(xlinkOut == nullptr) { - continue; - } - - auto streamName = xlinkOut->getStreamName(); - // Create DataOutputQueue's - outputQueueMap[streamName] = std::make_shared(connection, streamName); - - // Add callback for events - callbackIdMap[streamName] = outputQueueMap[streamName]->addCallback([this](std::string queueName, std::shared_ptr) { - // Lock first - std::unique_lock lock(eventMtx); - - // Check if size is equal or greater than EVENT_QUEUE_MAXIMUM_SIZE - if(eventQueue.size() >= EVENT_QUEUE_MAXIMUM_SIZE) { - auto numToRemove = eventQueue.size() - EVENT_QUEUE_MAXIMUM_SIZE + 1; - eventQueue.erase(eventQueue.begin(), eventQueue.begin() + numToRemove); - } - - // Add to the end of event queue - eventQueue.push_back(queueName); - - // notify the rest - eventCv.notify_all(); - }); - } - } catch(const std::exception&) { // close device (cleanup) close(); @@ -756,6 +785,12 @@ std::string Device::getQueueEvent(std::chrono::microseconds timeout) { return getQueueEvent(getOutputQueueNames(), timeout); } +std::vector Device::getConnectedCameras() { + checkClosed(); + + return client->call("getConnectedCameras").as>(); +} + // Convinience functions for querying current system information MemoryInfo Device::getDdrMemoryUsage() { checkClosed(); @@ -872,10 +907,84 @@ float Device::getSystemInformationLoggingRate() { } bool Device::startPipeline() { + // Check if has serialized pipeline + if(!hasPipeline) { + throw std::runtime_error("No pipeline given"); + } + + // Start the pipeline + bool ret = startPipeline(pipeline); + if(ret) { + // Remove the copy of the pipeline now as its not needed anymore + pipeline = Pipeline(nullptr); + } + + // Return result of starting the pipeline + return ret; +} + +bool Device::startPipeline(const Pipeline& pipeline) { checkClosed(); // first check if pipeline is not already started - if(isPipelineRunning()) return false; + if(isPipelineRunning()) { + throw std::runtime_error("Pipeline is already running"); + } + + PipelineSchema schema; + Assets assets; + std::vector assetStorage; + + // Mark the OpenVINO version and serialize the pipeline + OpenVINO::Version pipelineOpenvinoVersion; + pipeline.serialize(schema, assets, assetStorage, pipelineOpenvinoVersion); + if(openvinoVersion != pipelineOpenvinoVersion) { + throw std::runtime_error("Device booted with different OpenVINO version that pipeline requires"); + } + + // Open queues upfront, let queues know about data sizes (input queues) + // Go through Pipeline and check for 'XLinkIn' and 'XLinkOut' nodes + // and create corresponding default queues for them + for(const auto& kv : pipeline.getNodeMap()) { + const auto& node = kv.second; + const auto& xlinkIn = std::dynamic_pointer_cast(node); + if(xlinkIn == nullptr) { + continue; + } + // Create DataInputQueue's + inputQueueMap[xlinkIn->getStreamName()] = std::make_shared(connection, xlinkIn->getStreamName()); + // set max data size, for more verbosity + inputQueueMap[xlinkIn->getStreamName()]->setMaxDataSize(xlinkIn->getMaxDataSize()); + } + for(const auto& kv : pipeline.getNodeMap()) { + const auto& node = kv.second; + const auto& xlinkOut = std::dynamic_pointer_cast(node); + if(xlinkOut == nullptr) { + continue; + } + + auto streamName = xlinkOut->getStreamName(); + // Create DataOutputQueue's + outputQueueMap[streamName] = std::make_shared(connection, streamName); + + // Add callback for events + callbackIdMap[streamName] = outputQueueMap[streamName]->addCallback([this](std::string queueName, std::shared_ptr) { + // Lock first + std::unique_lock lock(eventMtx); + + // Check if size is equal or greater than EVENT_QUEUE_MAXIMUM_SIZE + if(eventQueue.size() >= EVENT_QUEUE_MAXIMUM_SIZE) { + auto numToRemove = eventQueue.size() - EVENT_QUEUE_MAXIMUM_SIZE + 1; + eventQueue.erase(eventQueue.begin(), eventQueue.begin() + numToRemove); + } + + // Add to the end of event queue + eventQueue.push_back(queueName); + + // notify the rest + eventCv.notify_all(); + }); + } // if debug if(spdlog::get_level() == spdlog::level::debug) { @@ -897,7 +1006,7 @@ bool Device::startPipeline() { // Transfer the whole assetStorage in a separate thread const std::string streamAssetStorage = "__stream_asset_storage"; - std::thread t1([this, &streamAssetStorage]() { + std::thread t1([this, &streamAssetStorage, &assetStorage]() { XLinkStream stream(*connection, streamAssetStorage, XLINK_USB_BUFFER_MAX_SIZE); int64_t offset = 0; do { diff --git a/src/pipeline/Pipeline.cpp b/src/pipeline/Pipeline.cpp index 18e637e46..00114bc35 100644 --- a/src/pipeline/Pipeline.cpp +++ b/src/pipeline/Pipeline.cpp @@ -22,20 +22,27 @@ Pipeline::Pipeline() : pimpl(std::make_shared()) { initialize(); } -/* -Pipeline::Pipeline(const Pipeline& p){ - pimpl = std::make_shared(); +Pipeline Pipeline::clone() const { + // TODO(themarpe) - Copy assets + + Pipeline clone; + + // Make a copy of PipelineImpl + clone.pimpl = std::make_shared(*impl()); + // All IDs remain the same, just switch out the actual nodes with copies // Copy all nodes - pimpl->globalProperties = p.getGlobalProperties(); - pimpl->nodes.reserve(p.pimpl->nodes.size()); - for(const auto& n : p.pimpl->nodes){ - auto clone = n->clone(); - clone->parent = std::weak_ptr(pimpl); - pimpl->nodes.push_back(clone); + for(const auto& kv : impl()->nodeMap) { + const auto& id = kv.first; + + // Swap out with a copy + clone.pimpl->nodeMap[id] = impl()->nodeMap.at(id)->clone(); + // Set parent to be the new pipeline + clone.pimpl->nodeMap[id]->parent = std::weak_ptr(clone.pimpl); } + + return clone; } -*/ Pipeline::Pipeline(const std::shared_ptr& pimpl) { this->pimpl = pimpl; diff --git a/src/pipeline/node/DetectionNetwork.cpp b/src/pipeline/node/DetectionNetwork.cpp index 6d3ff8d69..ae384c398 100644 --- a/src/pipeline/node/DetectionNetwork.cpp +++ b/src/pipeline/node/DetectionNetwork.cpp @@ -29,6 +29,10 @@ DetectionNetwork::Properties& DetectionNetwork::getPropertiesRef() { return properties; } +std::shared_ptr DetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + nlohmann::json DetectionNetwork::getProperties() { nlohmann::json j; nlohmann::to_json(j, properties); @@ -46,6 +50,10 @@ MobileNetDetectionNetwork::MobileNetDetectionNetwork(const std::shared_ptr MobileNetDetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + //-------------------------------------------------------------------- // YOLO //-------------------------------------------------------------------- @@ -73,5 +81,9 @@ void YoloDetectionNetwork::setIouThreshold(float thresh) { getPropertiesRef().iouThreshold = thresh; } +std::shared_ptr YoloDetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + } // namespace node } // namespace dai diff --git a/src/pipeline/node/SpatialDetectionNetwork.cpp b/src/pipeline/node/SpatialDetectionNetwork.cpp index 966812395..977ecf99c 100644 --- a/src/pipeline/node/SpatialDetectionNetwork.cpp +++ b/src/pipeline/node/SpatialDetectionNetwork.cpp @@ -13,6 +13,10 @@ namespace node { //-------------------------------------------------------------------- SpatialDetectionNetwork::SpatialDetectionNetwork(const std::shared_ptr& par, int64_t nodeId) : DetectionNetwork(par, nodeId) {} +std::shared_ptr SpatialDetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + std::string SpatialDetectionNetwork::getName() const { return "SpatialDetectionNetwork"; } @@ -55,6 +59,10 @@ MobileNetSpatialDetectionNetwork::MobileNetSpatialDetectionNetwork(const std::sh getPropertiesRef().nnFamily = DetectionNetworkType::MOBILENET; } +std::shared_ptr MobileNetSpatialDetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + //-------------------------------------------------------------------- // YOLO //-------------------------------------------------------------------- @@ -62,6 +70,10 @@ YoloSpatialDetectionNetwork::YoloSpatialDetectionNetwork(const std::shared_ptr

YoloSpatialDetectionNetwork::clone() { + return std::make_shared::type>(*this); +} + void YoloSpatialDetectionNetwork::setNumClasses(const int numClasses) { getPropertiesRef().classes = numClasses; } From 2cfe7453cbdd93fe0c4bbdd320bc2a88819e0e1d Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Wed, 28 Apr 2021 02:34:55 +0300 Subject: [PATCH 32/53] Add new field: Removed to object tracker status --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/datatype/Tracklets.hpp | 3 +++ shared/depthai-shared | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 11ef95434..d653f0824 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 "b71584129b101b30e4632678c19d33b020c04c36") +set(DEPTHAI_DEVICE_SIDE_COMMIT "3ff687833a5532b40e36e50db7d1ca49d65ec837") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/datatype/Tracklets.hpp b/include/depthai/pipeline/datatype/Tracklets.hpp index 2abdb1720..c45f8d3ae 100644 --- a/include/depthai/pipeline/datatype/Tracklets.hpp +++ b/include/depthai/pipeline/datatype/Tracklets.hpp @@ -41,6 +41,9 @@ inline std::ostream& operator<<(std::ostream& out, const Tracklet::TrackingStatu case Tracklet::TrackingStatus::LOST: out << "LOST"; break; + case Tracklet::TrackingStatus::REMOVED: + out << "REMOVED"; + break; } return out; } diff --git a/shared/depthai-shared b/shared/depthai-shared index 965d8bff2..4fcc95e7f 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 965d8bff23783d08ab332b03ec44fc96f3a56ffb +Subproject commit 4fcc95e7f6e109595ff9186d2e991d898f0b2448 From 3f2fb9d3e560f735048fffe301cc8bfbbe0cab7e Mon Sep 17 00:00:00 2001 From: alex-luxonis <60824841+alex-luxonis@users.noreply.github.com> Date: Wed, 28 Apr 2021 03:18:31 +0300 Subject: [PATCH 33/53] Address review comments. Note: The change in discussion (--parallel 8 in Readme) was already cherry-picked to develop (so no longer appears on this PR) --- README.md | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 20a494eb8..c5b4c53aa 100644 --- a/README.md +++ b/README.md @@ -43,27 +43,28 @@ Make sure submodules are updated ``` git submodule update --init --recursive ``` +ℹ️ For the `--parallel` argument of the commands below, specify a value `[num CPU cores]` or less, to reduce memory consumption during build. E.g.: `--parallel 8` **Static library** ``` mkdir build && cd build cmake .. -cmake --build . --parallel 8 +cmake --build . --parallel ``` **Dynamic library** ``` mkdir build && cd build cmake .. -D BUILD_SHARED_LIBS=ON -cmake --build . --parallel 8 +cmake --build . --parallel ``` ## Installing To install specify optional prefix and build target install ``` cmake .. -D CMAKE_INSTALL_PREFIX=[path/to/install/dir] -cmake --build . --parallel 8 -cmake --build . --target install --parallel 8 +cmake --build . --parallel +cmake --build . --target install --parallel ``` ## Running tests @@ -72,7 +73,7 @@ To run the tests build the library with the following options ``` mkdir build_tests && cd build_tests cmake .. -D DEPTHAI_TEST_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON -D DEPTHAI_BUILD_EXAMPLES=ON -cmake --build . --parallel 8 +cmake --build . --parallel ctest ``` From 6d84ac9217faf06361fe74d30607bcd5bc95b910 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 28 Apr 2021 00:46:21 +0300 Subject: [PATCH 34/53] clangformat cleanup --- src/pipeline/node/ColorCamera.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) mode change 100755 => 100644 src/pipeline/node/ColorCamera.cpp diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp old mode 100755 new mode 100644 index 51fb4717f..a356cb355 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -218,13 +218,13 @@ std::tuple ColorCamera::getVideoSize() const { int numW = properties.ispScale.horizNumerator; int denW = properties.ispScale.horizDenominator; if(numW > 0 && denW > 0) { - maxVideoWidth = getScaledSize(maxVideoWidth, numW, denW); + maxVideoWidth = getScaledSize(maxVideoWidth, numW, denW); } int numH = properties.ispScale.vertNumerator; int denH = properties.ispScale.vertDenominator; if(numH > 0 && denH > 0) { - maxVideoHeight = getScaledSize(maxVideoHeight, numH, denH); + maxVideoHeight = getScaledSize(maxVideoHeight, numH, denH); } return {maxVideoWidth, maxVideoHeight}; @@ -260,13 +260,13 @@ std::tuple ColorCamera::getStillSize() const { int numW = properties.ispScale.horizNumerator; int denW = properties.ispScale.horizDenominator; if(numW > 0 && denW > 0) { - maxStillWidth = getScaledSize(maxStillWidth, numW, denW); + maxStillWidth = getScaledSize(maxStillWidth, numW, denW); } int numH = properties.ispScale.vertNumerator; int denH = properties.ispScale.vertDenominator; if(numH > 0 && denH > 0) { - maxStillHeight = getScaledSize(maxStillHeight, numH, denH); + maxStillHeight = getScaledSize(maxStillHeight, numH, denH); } return {maxStillWidth, maxStillHeight}; From f62304d8b37cc19aeb7b8f535c1bdd51ae60d528 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 28 Apr 2021 01:26:50 +0300 Subject: [PATCH 35/53] Update FW: fix still capture with scaling, add FPS capping (with warnings) --- 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 97fa03734..0d4d63fd2 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 "c03b9979b83941cdc9feb1a29f5a1452234a65f9") +set(DEPTHAI_DEVICE_SIDE_COMMIT "9a713b5a5e4422944a2cf98ba177738d465da19f") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From bf1cbdd3c2992ca6ef4fa8435b625a65801176f0 Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 28 Apr 2021 13:31:27 +0300 Subject: [PATCH 36/53] Update FW: fix ImageManip U16 crop (for depth/subpixel disparity) Update shared: stereo_fixes merged --- 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 0d4d63fd2..f4f47b0c9 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 "9a713b5a5e4422944a2cf98ba177738d465da19f") +set(DEPTHAI_DEVICE_SIDE_COMMIT "49ca8b9d035ef51c3442d860ebf2e9d701807e44") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/shared/depthai-shared b/shared/depthai-shared index cf82fb1d8..7f55bf769 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit cf82fb1d879a32878f65d15359a5560bf6833470 +Subproject commit 7f55bf7692a327215b501abf7458a1f439ff6ab8 From bffa915bdaac684511c80c52f9fcc5c69f2271cd Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Wed, 28 Apr 2021 13:37:42 +0300 Subject: [PATCH 37/53] Update FW, fix CI build: depthai-shared PR merged --- 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 f4f47b0c9..0020832ed 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 "49ca8b9d035ef51c3442d860ebf2e9d701807e44") +set(DEPTHAI_DEVICE_SIDE_COMMIT "3b51648b0d96c9391d878eede0fd5fd9b44084ca") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") From b6cad5ad230118f89770d3566a2443f9eb9ccd57 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 29 Apr 2021 01:47:29 +0200 Subject: [PATCH 38/53] Deprecated 'startPipeline()' --- include/depthai/device/Device.hpp | 8 +++---- src/device/Device.cpp | 36 +++++++++++-------------------- 2 files changed, 16 insertions(+), 28 deletions(-) diff --git a/include/depthai/device/Device.hpp b/include/depthai/device/Device.hpp index f345dc4f2..d95c3f036 100644 --- a/include/depthai/device/Device.hpp +++ b/include/depthai/device/Device.hpp @@ -209,7 +209,7 @@ class Device { * * @return true if pipeline started, false otherwise */ - bool startPipeline(); + [[deprecated("Device(pipeline) starts the pipeline automatically. See Device() and startPipeline(pipeline) otherwise")]] bool startPipeline(); /** * Starts the execution of a given pipeline @@ -467,7 +467,7 @@ class Device { // private static void init(OpenVINO::Version version, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); void init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); - void init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd); + void init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd, tl::optional pipeline); void checkClosed() const; std::shared_ptr connection; @@ -514,9 +514,7 @@ class Device { class Impl; Pimpl pimpl; - // Serialized pipeline - bool hasPipeline = false; - Pipeline pipeline; + // OpenVINO version device was booted with OpenVINO::Version openvinoVersion; }; diff --git a/src/device/Device.cpp b/src/device/Device.cpp index d9b2de510..b726ec03e 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -377,28 +377,25 @@ void Device::init(OpenVINO::Version version, bool embeddedMvcmd, bool usb2Mode, // Specify the OpenVINO version openvinoVersion = version; - hasPipeline = false; spdlog::debug("Device - OpenVINO version: {}", OpenVINO::getVersionName(openvinoVersion)); - init2(embeddedMvcmd, usb2Mode, pathToMvcmd); + init2(embeddedMvcmd, usb2Mode, pathToMvcmd, tl::nullopt); } void Device::init(const Pipeline& pipeline, bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd) { // Initalize depthai library if not already initialize(); - // Mark the OpenVINO version and make a copy of the pipeline - this->pipeline = pipeline.clone(); - openvinoVersion = this->pipeline.getOpenVINOVersion(); - hasPipeline = true; + // Mark the OpenVINO version + openvinoVersion = pipeline.getOpenVINOVersion(); spdlog::debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(openvinoVersion)); - init2(embeddedMvcmd, usb2Mode, pathToMvcmd); + init2(embeddedMvcmd, usb2Mode, pathToMvcmd, pipeline); } -void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd) { +void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToMvcmd, tl::optional pipeline) { // Set logging pattern of device (device id + shared pattern) pimpl->setPattern(fmt::format("[{}] {}", deviceInfo.getMxId(), LOG_DEFAULT_PATTERN)); @@ -594,6 +591,11 @@ void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToM // Sets system inforation logging rate. By default 1s setSystemInformationLoggingRate(DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ); + // Starts pipeline if given + if(pipeline) { + startPipeline(*pipeline); + } + } catch(const std::exception&) { // close device (cleanup) close(); @@ -907,26 +909,14 @@ float Device::getSystemInformationLoggingRate() { } bool Device::startPipeline() { - // Check if has serialized pipeline - if(!hasPipeline) { - throw std::runtime_error("No pipeline given"); - } - - // Start the pipeline - bool ret = startPipeline(pipeline); - if(ret) { - // Remove the copy of the pipeline now as its not needed anymore - pipeline = Pipeline(nullptr); - } - - // Return result of starting the pipeline - return ret; + // Deprecated + return true; } bool Device::startPipeline(const Pipeline& pipeline) { checkClosed(); - // first check if pipeline is not already started + // first check if pipeline is not already running if(isPipelineRunning()) { throw std::runtime_error("Pipeline is already running"); } From a1c98287d9eb359ccf06ae8bbafe5c282c4bc130 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 29 Apr 2021 01:48:23 +0200 Subject: [PATCH 39/53] Removed deprecated functions from examples --- examples/src/camera_mobilenet_example.cpp | 4 +--- examples/src/camera_mobilenet_sync_example.cpp | 1 - examples/src/camera_preview_example.cpp | 14 ++++++++++++-- examples/src/camera_video_example.cpp | 4 +--- examples/src/color_camera_control_example.cpp | 5 +---- examples/src/device_queue_event_example.cpp | 4 +--- examples/src/h264_encoding_example.cpp | 4 +--- examples/src/image_manip_example.cpp | 1 - examples/src/image_manip_warp_example.cpp | 1 - examples/src/mjpeg_encoding_example.cpp | 4 +--- .../src/mobilenet_device_side_decoding_example.cpp | 4 +--- examples/src/mono_camera_example.cpp | 4 +--- examples/src/object_tracker_example.cpp | 4 +--- examples/src/opencv_support_example.cpp | 5 +---- .../src/spatial_location_calculator_example.cpp | 3 +-- examples/src/spatial_mobilenet_example.cpp | 9 ++++----- examples/src/spatial_mobilenet_mono_example.cpp | 9 ++++----- examples/src/spatial_object_tracker_example.cpp | 4 +--- examples/src/spatial_tiny_yolo_example.cpp | 9 ++++----- examples/src/stereo_example.cpp | 3 +-- examples/src/system_information_example.cpp | 4 ++-- .../tiny_yolo_v3_device_side_decoding_example.cpp | 4 +--- .../tiny_yolo_v4_device_side_decoding_example.cpp | 4 +--- examples/src/webcam_mobilenet_example.cpp | 2 -- tests/src/color_camera_node_test.cpp | 1 - tests/src/image_manip_node_test.cpp | 1 - tests/src/neural_network_test.cpp | 4 ++-- 27 files changed, 43 insertions(+), 73 deletions(-) diff --git a/examples/src/camera_mobilenet_example.cpp b/examples/src/camera_mobilenet_example.cpp index 60b99894a..5f094058d 100644 --- a/examples/src/camera_mobilenet_example.cpp +++ b/examples/src/camera_mobilenet_example.cpp @@ -58,10 +58,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); cv::Mat frame; auto preview = d.getOutputQueue("preview"); diff --git a/examples/src/camera_mobilenet_sync_example.cpp b/examples/src/camera_mobilenet_sync_example.cpp index a8039b59a..e09d5fbe8 100644 --- a/examples/src/camera_mobilenet_sync_example.cpp +++ b/examples/src/camera_mobilenet_sync_example.cpp @@ -56,7 +56,6 @@ int main(int argc, char** argv) { // Connect to device and start pipeline dai::Device device(pipeline); - device.startPipeline(); // Create input & output queues auto previewQueue = device.getOutputQueue("preview"); diff --git a/examples/src/camera_preview_example.cpp b/examples/src/camera_preview_example.cpp index fdc33aa9c..70062ea60 100644 --- a/examples/src/camera_preview_example.cpp +++ b/examples/src/camera_preview_example.cpp @@ -28,8 +28,18 @@ int main() { using namespace std; dai::Pipeline p = createCameraPipeline(); - dai::Device d(p); - d.startPipeline(); + + // Start the pipeline + dai::Device d; + + cout << "Connected cameras: "; + for(const auto& cam : d.getConnectedCameras()){ + cout << static_cast(cam) << " "; + } + cout << endl; + + // Start the pipeline + d.startPipeline(p); cv::Mat frame; auto preview = d.getOutputQueue("preview"); diff --git a/examples/src/camera_video_example.cpp b/examples/src/camera_video_example.cpp index 9595579b0..c610446b9 100644 --- a/examples/src/camera_video_example.cpp +++ b/examples/src/camera_video_example.cpp @@ -31,10 +31,8 @@ int main() { // Create pipeline dai::Pipeline p = createCameraFullPipeline(); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); cv::Mat frame; auto video = d.getOutputQueue("video"); diff --git a/examples/src/color_camera_control_example.cpp b/examples/src/color_camera_control_example.cpp index 56715a033..5bd33ade4 100644 --- a/examples/src/color_camera_control_example.cpp +++ b/examples/src/color_camera_control_example.cpp @@ -63,7 +63,7 @@ int main() { videoEncoder->bitstream.link(videoMjpegOut->input); stillEncoder->bitstream.link(stillMjpegOut->input); - // Connect to device + // Connect and start the pipeline dai::Device dev(pipeline); // Create data queues @@ -73,9 +73,6 @@ int main() { auto videoQueue = dev.getOutputQueue("video"); auto stillQueue = dev.getOutputQueue("still"); - // Start pipeline - dev.startPipeline(); - // Max crop_x & crop_y float max_crop_x = (colorCam->getResolutionWidth() - colorCam->getVideoWidth()) / (float)colorCam->getResolutionWidth(); float max_crop_y = (colorCam->getResolutionHeight() - colorCam->getVideoHeight()) / (float)colorCam->getResolutionHeight(); diff --git a/examples/src/device_queue_event_example.cpp b/examples/src/device_queue_event_example.cpp index aca4edd6e..4bfaf70b2 100644 --- a/examples/src/device_queue_event_example.cpp +++ b/examples/src/device_queue_event_example.cpp @@ -36,10 +36,8 @@ int main(int argc, char** argv) { colorCam->preview.link(xout2->input); videnc->bitstream.link(xout->input); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); // Sets queues size and behaviour d.getOutputQueue("mjpeg", 8, false); diff --git a/examples/src/h264_encoding_example.cpp b/examples/src/h264_encoding_example.cpp index d366a4c0e..ee1659226 100644 --- a/examples/src/h264_encoding_example.cpp +++ b/examples/src/h264_encoding_example.cpp @@ -43,10 +43,8 @@ int main(int argc, char** argv) { colorCam->preview.link(xout2->input); videnc->bitstream.link(xout->input); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto myfile = std::fstream(h264Path, std::ios::out | std::ios::binary); diff --git a/examples/src/image_manip_example.cpp b/examples/src/image_manip_example.cpp index cd562567c..a3707b7b0 100644 --- a/examples/src/image_manip_example.cpp +++ b/examples/src/image_manip_example.cpp @@ -55,7 +55,6 @@ int main() { // Connect to device and start pipeline dai::Device device(pipeline); - device.startPipeline(); // Create input & output queues auto previewQueue = device.getOutputQueue("preview", 8, false); diff --git a/examples/src/image_manip_warp_example.cpp b/examples/src/image_manip_warp_example.cpp index 886b872aa..48595fabe 100644 --- a/examples/src/image_manip_warp_example.cpp +++ b/examples/src/image_manip_warp_example.cpp @@ -85,7 +85,6 @@ int main() { // Connect to device and start pipeline dai::Device device(pipeline); - device.startPipeline(); // Create input & output queues auto previewQueue = device.getOutputQueue("preview", 8, false); diff --git a/examples/src/mjpeg_encoding_example.cpp b/examples/src/mjpeg_encoding_example.cpp index 15c4c7bdc..075978fee 100644 --- a/examples/src/mjpeg_encoding_example.cpp +++ b/examples/src/mjpeg_encoding_example.cpp @@ -36,10 +36,8 @@ int main(int argc, char** argv) { colorCam->preview.link(xout2->input); videnc->bitstream.link(xout->input); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto mjpegQueue = d.getOutputQueue("mjpeg", 8, false); auto previewQueue = d.getOutputQueue("preview", 8, false); diff --git a/examples/src/mobilenet_device_side_decoding_example.cpp b/examples/src/mobilenet_device_side_decoding_example.cpp index 1794cb5ac..29347768f 100644 --- a/examples/src/mobilenet_device_side_decoding_example.cpp +++ b/examples/src/mobilenet_device_side_decoding_example.cpp @@ -63,10 +63,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/mono_camera_example.cpp b/examples/src/mono_camera_example.cpp index 9f2a7e4f9..730b736d9 100644 --- a/examples/src/mono_camera_example.cpp +++ b/examples/src/mono_camera_example.cpp @@ -30,10 +30,8 @@ int main() { // Create pipeline dai::Pipeline p = createMonoPipeline(); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); cv::Mat frame; auto monoQueue = d.getOutputQueue("mono"); diff --git a/examples/src/object_tracker_example.cpp b/examples/src/object_tracker_example.cpp index 30ef1bfb8..c691642ad 100644 --- a/examples/src/object_tracker_example.cpp +++ b/examples/src/object_tracker_example.cpp @@ -71,10 +71,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto tracklets = d.getOutputQueue("tracklets", 4, false); diff --git a/examples/src/opencv_support_example.cpp b/examples/src/opencv_support_example.cpp index f042be393..4b8ca5541 100644 --- a/examples/src/opencv_support_example.cpp +++ b/examples/src/opencv_support_example.cpp @@ -34,12 +34,9 @@ int main() { // Create pipeline dai::Pipeline p = createCameraFullPipeline(); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); - auto video = d.getOutputQueue("video"); auto preview = d.getOutputQueue("preview"); diff --git a/examples/src/spatial_location_calculator_example.cpp b/examples/src/spatial_location_calculator_example.cpp index d0762ed75..fcba23bd6 100644 --- a/examples/src/spatial_location_calculator_example.cpp +++ b/examples/src/spatial_location_calculator_example.cpp @@ -68,9 +68,8 @@ int main() { spatialDataCalculator->out.link(xoutSpatialData->input); xinSpatialCalcConfig->out.link(spatialDataCalculator->inputConfig); - // CONNECT TO DEVICE + // Connect and start the pipeline dai::Device d(p); - d.startPipeline(); auto depthQueue = d.getOutputQueue("depth", 8, false); auto spatialCalcQueue = d.getOutputQueue("spatialData", 8, false); diff --git a/examples/src/spatial_mobilenet_example.cpp b/examples/src/spatial_mobilenet_example.cpp index 338c5bc1e..c86b7e6d3 100644 --- a/examples/src/spatial_mobilenet_example.cpp +++ b/examples/src/spatial_mobilenet_example.cpp @@ -61,10 +61,11 @@ dai::Pipeline createNNPipeline(std::string nnPath) { // Link plugins CAM -> NN -> XLINK colorCam->preview.link(spatialDetectionNetwork->input); - if(syncNN) + if(syncNN) { spatialDetectionNetwork->passthrough.link(xoutRgb->input); - else + } else { colorCam->preview.link(xoutRgb->input); + } spatialDetectionNetwork->out.link(xoutNN->input); spatialDetectionNetwork->boundingBoxMapping.link(xoutBoundingBoxDepthMapping->input); @@ -91,10 +92,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/spatial_mobilenet_mono_example.cpp b/examples/src/spatial_mobilenet_mono_example.cpp index 9cbd58025..2b95136f5 100644 --- a/examples/src/spatial_mobilenet_mono_example.cpp +++ b/examples/src/spatial_mobilenet_mono_example.cpp @@ -63,10 +63,11 @@ dai::Pipeline createNNPipeline(std::string nnPath) { // Link plugins CAM -> NN -> XLINK imageManip->out.link(spatialDetectionNetwork->input); - if(syncNN) + if(syncNN) { spatialDetectionNetwork->passthrough.link(xlinkOut->input); - else + } else { imageManip->out.link(xlinkOut->input); + } spatialDetectionNetwork->out.link(nnOut->input); spatialDetectionNetwork->boundingBoxMapping.link(depthRoiMap->input); @@ -93,10 +94,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/spatial_object_tracker_example.cpp b/examples/src/spatial_object_tracker_example.cpp index 2692e2809..b414f5f9e 100644 --- a/examples/src/spatial_object_tracker_example.cpp +++ b/examples/src/spatial_object_tracker_example.cpp @@ -94,10 +94,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto tracklets = d.getOutputQueue("tracklets", 4, false); diff --git a/examples/src/spatial_tiny_yolo_example.cpp b/examples/src/spatial_tiny_yolo_example.cpp index 19a67a602..76f0a5a78 100644 --- a/examples/src/spatial_tiny_yolo_example.cpp +++ b/examples/src/spatial_tiny_yolo_example.cpp @@ -75,10 +75,11 @@ dai::Pipeline createNNPipeline(std::string nnPath) { // Link plugins CAM -> NN -> XLINK colorCam->preview.link(spatialDetectionNetwork->input); - if(syncNN) + if(syncNN) { spatialDetectionNetwork->passthrough.link(xoutRgb->input); - else + } else { colorCam->preview.link(xoutRgb->input); + } spatialDetectionNetwork->out.link(xoutNN->input); spatialDetectionNetwork->boundingBoxMapping.link(xoutBoundingBoxDepthMapping->input); @@ -105,10 +106,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/stereo_example.cpp b/examples/src/stereo_example.cpp index 732d5d05b..61afac83d 100644 --- a/examples/src/stereo_example.cpp +++ b/examples/src/stereo_example.cpp @@ -87,9 +87,8 @@ int main() { monoRight->out.link(xoutRight->input); } - // CONNECT TO DEVICE + // Connect and start the pipeline dai::Device d(p); - d.startPipeline(); auto leftQueue = d.getOutputQueue("left", 8, false); auto rightQueue = d.getOutputQueue("right", 8, false); diff --git a/examples/src/system_information_example.cpp b/examples/src/system_information_example.cpp index efae09c41..d33f4f2d1 100644 --- a/examples/src/system_information_example.cpp +++ b/examples/src/system_information_example.cpp @@ -25,7 +25,7 @@ int main() { sysLog->out.link(xout->input); // Connect to device - dai::Device device(pipeline); + dai::Device device; // Create 'sysinfo' queue auto queue = device.getOutputQueue("sysinfo"); @@ -38,7 +38,7 @@ int main() { printf("Cmx used / total - %.2f / %.2f MiB\n", cmx.used / (1024.0f * 1024.0f), cmx.total / (1024.0f * 1024.0f)); // Start pipeline - device.startPipeline(); + device.startPipeline(pipeline); while(1) { auto sysInfo = queue->get(); diff --git a/examples/src/tiny_yolo_v3_device_side_decoding_example.cpp b/examples/src/tiny_yolo_v3_device_side_decoding_example.cpp index 6df7ac9e1..18b2fd1db 100644 --- a/examples/src/tiny_yolo_v3_device_side_decoding_example.cpp +++ b/examples/src/tiny_yolo_v3_device_side_decoding_example.cpp @@ -76,10 +76,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/tiny_yolo_v4_device_side_decoding_example.cpp b/examples/src/tiny_yolo_v4_device_side_decoding_example.cpp index 211f196a6..9fcb2ea31 100644 --- a/examples/src/tiny_yolo_v4_device_side_decoding_example.cpp +++ b/examples/src/tiny_yolo_v4_device_side_decoding_example.cpp @@ -81,10 +81,8 @@ int main(int argc, char** argv) { // Create pipeline dai::Pipeline p = createNNPipeline(nnPath); - // Connect to device with above created pipeline + // Connect and start the pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); auto preview = d.getOutputQueue("preview", 4, false); auto detections = d.getOutputQueue("detections", 4, false); diff --git a/examples/src/webcam_mobilenet_example.cpp b/examples/src/webcam_mobilenet_example.cpp index c873466cd..3a517ce7a 100644 --- a/examples/src/webcam_mobilenet_example.cpp +++ b/examples/src/webcam_mobilenet_example.cpp @@ -50,8 +50,6 @@ int main(int argc, char** argv) { // Connect to device with above created pipeline dai::Device d(p); - // Start the pipeline - d.startPipeline(); cv::Mat frame; auto in = d.getInputQueue("nn_in"); diff --git a/tests/src/color_camera_node_test.cpp b/tests/src/color_camera_node_test.cpp index 8b67023dd..549d03d99 100644 --- a/tests/src/color_camera_node_test.cpp +++ b/tests/src/color_camera_node_test.cpp @@ -39,7 +39,6 @@ int main() { if(found) { dai::Device d(p, deviceInfo); - d.startPipeline(); auto previewQueue = d.getOutputQueue("preview", 8, true); diff --git a/tests/src/image_manip_node_test.cpp b/tests/src/image_manip_node_test.cpp index cba103ea4..e5a303e3f 100644 --- a/tests/src/image_manip_node_test.cpp +++ b/tests/src/image_manip_node_test.cpp @@ -41,7 +41,6 @@ int main() { if(found) { dai::Device d(p, deviceInfo); - d.startPipeline(); auto in = d.getInputQueue("in"); auto out = d.getOutputQueue("out"); diff --git a/tests/src/neural_network_test.cpp b/tests/src/neural_network_test.cpp index fa0c0cd69..2f4bfbec1 100644 --- a/tests/src/neural_network_test.cpp +++ b/tests/src/neural_network_test.cpp @@ -42,7 +42,7 @@ TEST_CASE("Neural network node data checks") { auto pipeline = createNeuralNetworkPipeline(); - dai::Device device(pipeline); + dai::Device device(pipeline.getOpenVINOVersion()); std::atomic receivedLogMessage{false}; @@ -55,7 +55,7 @@ TEST_CASE("Neural network node data checks") { }); // Start pipeline and feed correct sized data in various forms (Planar BGR 300*300*3 for mobilenet) - device.startPipeline(); + device.startPipeline(pipeline); // Iterate 10 times for(int i = 0; i < 10; i++) { From a25d18028e01ad09b28b3617f8f6ca6bcf923655 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 29 Apr 2021 03:28:29 +0200 Subject: [PATCH 40/53] Fixed sanitizers for examples --- examples/CMakeLists.txt | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 794832f56..3454d166e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -3,6 +3,7 @@ option(DEPTHAI_TEST_EXAMPLES "Test examples - examples will be ran as a part of # Dependencies find_package(OpenCV REQUIRED) +find_package(Sanitizers) # Create utility library add_library(utility src/utility.cpp) @@ -13,13 +14,16 @@ macro(dai_add_example example_name example_src) add_executable("${example_name}" "${example_src}") target_link_libraries("${example_name}" PRIVATE utility depthai::opencv ${OpenCV_LIBS}) + # Add sanitizers for example + add_sanitizers(${example_name}) + # Add to clangformat target target_clangformat_setup(${example_name} "") # parse the rest of the arguments set(arguments ${ARGV}) list(REMOVE_AT arguments 0 1) - + # If 'DEPTHAI_TEST_EXAMPLES' is ON, then examples will be part of the test suite if(DEPTHAI_TEST_EXAMPLES) add_test(NAME ${example_name} COMMAND ${CMAKE_COMMAND} @@ -28,16 +32,13 @@ macro(dai_add_example example_name example_src) ) # Sets a regex catching any logged warnings, errors or critical (coming either from device or host) - set_tests_properties (${example_name} PROPERTIES FAIL_REGULAR_EXPRESSION "\\[warning\\];\\[error\\];\\[critical\\]") - - # Add sanitizers for tests as well - add_sanitizers(${example_name}) + set_tests_properties (${example_name} PROPERTIES FAIL_REGULAR_EXPRESSION "\\[warning\\];\\[error\\];\\[critical\\]") # Add ubsan halt on error set_tests_properties(${example_name} PROPERTIES ENVIRONMENT "UBSAN_OPTIONS=halt_on_error=1") endif() -endmacro() +endmacro() # Create a custom target which runs all examples for 10 seconds max, and check if they executed without errors From edc7f81bad04dc3cfde8a6225c9528a5420ff659 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Thu, 29 Apr 2021 03:37:35 +0200 Subject: [PATCH 41/53] Updated device side with 'getConnectedCameras' --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- src/device/Device.cpp | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 11ef95434..e9abd4fc6 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 "b71584129b101b30e4632678c19d33b020c04c36") +set(DEPTHAI_DEVICE_SIDE_COMMIT "024f66e3c54509867585c4079c949b57ac9d8bdf") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/src/device/Device.cpp b/src/device/Device.cpp index b726ec03e..f5d81383e 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -593,7 +593,9 @@ void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToM // Starts pipeline if given if(pipeline) { - startPipeline(*pipeline); + if(!startPipeline(*pipeline)){ + throw std::runtime_error("Couldn't start the pipeline"); + } } } catch(const std::exception&) { From 3e3b8cee7aeedb07cf9c345b2a7c56f93e0b3fcc Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sat, 1 May 2021 01:38:29 +0200 Subject: [PATCH 42/53] Applied formatting --- examples/src/camera_preview_example.cpp | 2 +- examples/src/stereo_example.cpp | 6 +++--- src/device/Device.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/src/camera_preview_example.cpp b/examples/src/camera_preview_example.cpp index 70062ea60..82b7c99c7 100644 --- a/examples/src/camera_preview_example.cpp +++ b/examples/src/camera_preview_example.cpp @@ -33,7 +33,7 @@ int main() { dai::Device d; cout << "Connected cameras: "; - for(const auto& cam : d.getConnectedCameras()){ + for(const auto& cam : d.getConnectedCameras()) { cout << static_cast(cam) << " "; } cout << endl; diff --git a/examples/src/stereo_example.cpp b/examples/src/stereo_example.cpp index 9ca127421..935698e69 100644 --- a/examples/src/stereo_example.cpp +++ b/examples/src/stereo_example.cpp @@ -77,7 +77,7 @@ int main() { stereo->rectifiedRight.link(xoutRectifR->input); } stereo->disparity.link(xoutDisp->input); - if (outputDepth) { + if(outputDepth) { stereo->depth.link(xoutDepth->input); } @@ -121,13 +121,13 @@ int main() { if(outputRectified) { auto rectifL = rectifLeftQueue->get(); cv::Mat rectifiedLeftFrame = rectifL->getFrame(); - //cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); + // cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); cv::imshow("rectified_left", rectifiedLeftFrame); auto rectifR = rectifRightQueue->get(); cv::Mat rectifiedRightFrame = rectifR->getFrame(); - //cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); + // cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); cv::imshow("rectified_right", rectifiedRightFrame); } } diff --git a/src/device/Device.cpp b/src/device/Device.cpp index f5d81383e..ed3c425c5 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -593,7 +593,7 @@ void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToM // Starts pipeline if given if(pipeline) { - if(!startPipeline(*pipeline)){ + if(!startPipeline(*pipeline)) { throw std::runtime_error("Couldn't start the pipeline"); } } From 0ef855ed2adedf9ee4bf790e037916cf28ac9c14 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sat, 1 May 2021 01:43:05 +0200 Subject: [PATCH 43/53] Updated README.md --- README.md | 102 +++++++++++++++++++++++++++++++++++++++--------------- 1 file changed, 75 insertions(+), 27 deletions(-) diff --git a/README.md b/README.md index c5b4c53aa..65abe2705 100644 --- a/README.md +++ b/README.md @@ -21,66 +21,114 @@ MacOS: `brew install libusb` Linux: `sudo apt install libusb-1.0-0-dev` -## Using as library +## Integration -To use this library in your own project you can use CMake `add_subdirectory` pointing to the root of this repository -Optionally append `EXCLUDE_FROM_ALL` to hide depthai-core related targets, etc... +### CMake + +Targets available to link to are: + - depthai::core - Core library, without using opencv internally + - depthai::opencv - Core + support for opencv related helper functions (requires OpenCV4) + +#### Using find_package + +Build static or dynamic version of library and install (See: [Building](##building) and [Installing](##installing)) + +Add `find_package` and `target_link_libraries` to your project +``` +find_package(depthai CONFIG REQUIRED) +... +target_link_libraries([my-app] PRIVATE depthai::opencv) ``` -add_subdirectory(depthai-core) + +And point CMake to either build directory or install directory: +``` +-D depthai_DIR=depthai-core/build ``` or ``` -add_subdirectory(depthai-core EXCLUDE_FROM_ALL) +-D depthai_DIR=depthai-core/build/install/lib/cmake/depthai ``` -And at the end link to your target (PUBLIC or PRIVATE depending on your needs) + +If library was installed to default search path like `/usr/local` on Linux, specifying `depthai_DIR` isn't necessary as CMake will find it automatically. + +#### Using add_subdirectory + +This method is more intrusive but simpler as it doesn't require building the library separately. + +Add `add_subdirectory` which points to `depthai-core` folder **before** project command. Then link to any required targets. ``` -target_link_libraries(my-app PUBLIC depthai-core) +add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/depthai-core EXCLUDE_FROM_ALL) +... +project(my-app) +... +target_link_libraries([my-app] PRIVATE depthai::opencv) ``` +### Non-CMake integration (Visual Studio, Xcode, CodeBlocks, ...) + +To integrate into a different build system than CMake, prefered way is compiling as dynamic library and pointing to correct include directories. +1. First build as dynamic library: [Building Dynamic library](###dynamic-library) +2. Then install: [Installing](##installing) +3. Set needed library directories: + - `build/install/lib` (for linking to either depthai-core or depthai-opencv) + - `build/install/bin` (for .dll's) +4. And include directories + - `build/install/include` (library headers) + - `build/install/include/depthai-shared/3rdparty` (shared 3rdparty headers) + - `build/install/lib/cmake/depthai/dependencies/include` (dependencies headers) + +> ℹ️ Threading library might need to be linked to explicitly. + ## Building -Make sure submodules are updated +Make sure submodules are updated ``` git submodule update --init --recursive ``` -ℹ️ For the `--parallel` argument of the commands below, specify a value `[num CPU cores]` or less, to reduce memory consumption during build. E.g.: `--parallel 8` -**Static library** +> ℹ️ To speed up build times, use `cmake --build build --parallel [num CPU cores]` (CMake >= 3.12). +For older versions use: Linux/macOS: `cmake --build build -- -j[num CPU cores]`, MSVC: `cmake --build build -- /MP[num CPU cores]` + +### Static library ``` -mkdir build && cd build -cmake .. -cmake --build . --parallel +cmake -H. -Bbuild +cmake --build build ``` -**Dynamic library** +### Dynamic library ``` -mkdir build && cd build -cmake .. -D BUILD_SHARED_LIBS=ON -cmake --build . --parallel +cmake -H. -Bbuild -D BUILD_SHARED_LIBS=ON +cmake --build build ``` ## Installing To install specify optional prefix and build target install ``` -cmake .. -D CMAKE_INSTALL_PREFIX=[path/to/install/dir] -cmake --build . --parallel -cmake --build . --target install --parallel +cmake -H. -Bbuild -D CMAKE_INSTALL_PREFIX=[path/to/install/dir] +cmake --build build +cmake --build build --target install ``` +If `CMAKE_INSTALL_PREFIX` isn't specified, the library is installed under build folder `install`. + ## Running tests To run the tests build the library with the following options ``` -mkdir build_tests && cd build_tests -cmake .. -D DEPTHAI_TEST_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON -D DEPTHAI_BUILD_EXAMPLES=ON -cmake --build . --parallel +cmake -H. -Bbuild -D DEPTHAI_TEST_EXAMPLES=ON -D DEPTHAI_BUILD_TESTS=ON -D DEPTHAI_BUILD_EXAMPLES=ON +cmake --build build +``` + +Then navigate to `build` folder and run `ctest` +``` +cd build ctest ``` ## Style check -The library uses clang format to enforce a certain style. -If a style check is failing, run the `clangformat` target, check the output and push changes +The library uses clang format to enforce a certain coding style. +If a style check is failing, run the `clangformat` target, check the output and push changes. To use this target clang format must be installed, preferably clang-format-10 ``` @@ -89,7 +137,7 @@ sudo apt install clang-format-10 And to apply formatting ``` -cmake --build [build/dir] --target clangformat +cmake --build build --target clangformat ``` ## Documentation generation @@ -120,7 +168,7 @@ This retains the libraries source code, so that debugger can step through it (th ## Troubleshooting ### Hunter -Hunter is a CMake-only dependency manager for C/C++ projects. +Hunter is a CMake-only dependency manager for C/C++ projects. If you are stuck with error message which mentions external libraries (subdirectory of `.hunter`) like the following: ``` From 525366cb4244683e68d0dff3349dc47b21f62cc0 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sat, 1 May 2021 13:52:19 +0300 Subject: [PATCH 44/53] Update FW with fix for resource allocation when depth is enabled; fix system_information_example --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- examples/src/system_information_example.cpp | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index a69ed775f..21e6d8d86 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 "d179193abd443eca5ca134232aabd874e5d78d18") +set(DEPTHAI_DEVICE_SIDE_COMMIT "a30a3c397f7daa4fc4b15ec8741763b76fe07e9a") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/src/system_information_example.cpp b/examples/src/system_information_example.cpp index d33f4f2d1..2d70aadec 100644 --- a/examples/src/system_information_example.cpp +++ b/examples/src/system_information_example.cpp @@ -26,6 +26,8 @@ int main() { // Connect to device dai::Device device; + // Start pipeline + device.startPipeline(pipeline); // Create 'sysinfo' queue auto queue = device.getOutputQueue("sysinfo"); @@ -37,9 +39,6 @@ int main() { dai::MemoryInfo cmx = device.getCmxMemoryUsage(); printf("Cmx used / total - %.2f / %.2f MiB\n", cmx.used / (1024.0f * 1024.0f), cmx.total / (1024.0f * 1024.0f)); - // Start pipeline - device.startPipeline(pipeline); - while(1) { auto sysInfo = queue->get(); printSystemInformation(*sysInfo); From 7d275ef20b37ef49dc10ac24af06e657da0cbd69 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sat, 1 May 2021 14:56:17 +0300 Subject: [PATCH 45/53] Apply formatting --- examples/src/camera_preview_example.cpp | 2 +- examples/src/stereo_example.cpp | 6 +++--- src/device/Device.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/src/camera_preview_example.cpp b/examples/src/camera_preview_example.cpp index 70062ea60..82b7c99c7 100644 --- a/examples/src/camera_preview_example.cpp +++ b/examples/src/camera_preview_example.cpp @@ -33,7 +33,7 @@ int main() { dai::Device d; cout << "Connected cameras: "; - for(const auto& cam : d.getConnectedCameras()){ + for(const auto& cam : d.getConnectedCameras()) { cout << static_cast(cam) << " "; } cout << endl; diff --git a/examples/src/stereo_example.cpp b/examples/src/stereo_example.cpp index 9ca127421..935698e69 100644 --- a/examples/src/stereo_example.cpp +++ b/examples/src/stereo_example.cpp @@ -77,7 +77,7 @@ int main() { stereo->rectifiedRight.link(xoutRectifR->input); } stereo->disparity.link(xoutDisp->input); - if (outputDepth) { + if(outputDepth) { stereo->depth.link(xoutDepth->input); } @@ -121,13 +121,13 @@ int main() { if(outputRectified) { auto rectifL = rectifLeftQueue->get(); cv::Mat rectifiedLeftFrame = rectifL->getFrame(); - //cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); + // cv::flip(rectifiedLeftFrame, rectifiedLeftFrame, 1); cv::imshow("rectified_left", rectifiedLeftFrame); auto rectifR = rectifRightQueue->get(); cv::Mat rectifiedRightFrame = rectifR->getFrame(); - //cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); + // cv::flip(rectifiedRightFrame, rectifiedRightFrame, 1); cv::imshow("rectified_right", rectifiedRightFrame); } } diff --git a/src/device/Device.cpp b/src/device/Device.cpp index f5d81383e..ed3c425c5 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -593,7 +593,7 @@ void Device::init2(bool embeddedMvcmd, bool usb2Mode, const std::string& pathToM // Starts pipeline if given if(pipeline) { - if(!startPipeline(*pipeline)){ + if(!startPipeline(*pipeline)) { throw std::runtime_error("Couldn't start the pipeline"); } } From c71fab7465ed96758f5ad46482547dfaa75b236d Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Sat, 1 May 2021 15:12:05 +0300 Subject: [PATCH 46/53] Move queue init after pipeline start in system information example --- examples/src/system_information_example.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/examples/src/system_information_example.cpp b/examples/src/system_information_example.cpp index 2d70aadec..5a4e67524 100644 --- a/examples/src/system_information_example.cpp +++ b/examples/src/system_information_example.cpp @@ -26,11 +26,6 @@ int main() { // Connect to device dai::Device device; - // Start pipeline - device.startPipeline(pipeline); - - // Create 'sysinfo' queue - auto queue = device.getOutputQueue("sysinfo"); // Query device (before pipeline starts) dai::MemoryInfo ddr = device.getDdrMemoryUsage(); @@ -39,6 +34,12 @@ int main() { dai::MemoryInfo cmx = device.getCmxMemoryUsage(); printf("Cmx used / total - %.2f / %.2f MiB\n", cmx.used / (1024.0f * 1024.0f), cmx.total / (1024.0f * 1024.0f)); + // Start pipeline + device.startPipeline(pipeline); + + // Create 'sysinfo' queue + auto queue = device.getOutputQueue("sysinfo"); + while(1) { auto sysInfo = queue->get(); printSystemInformation(*sysInfo); From 5d88b96904d8c0da4cfd931834e9b3dba8a7fe9a Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Sun, 2 May 2021 23:11:36 +0200 Subject: [PATCH 47/53] Added build information and config.hpp to remove the need to specify compile definitions --- CMakeLists.txt | 36 ++++++++++++++++--- cmake/config.hpp.in | 14 ++++++++ cmake/version.hpp.in | 26 ++++++++------ docs/Doxyfile.in | 2 +- .../depthai/pipeline/datatype/ImgFrame.hpp | 36 +++++++++++++++---- include/depthai/utility/Initialization.hpp | 4 ++- src/utility/Initialization.cpp | 10 +++++- tests/integration/src/main.cpp | 2 +- 8 files changed, 104 insertions(+), 26 deletions(-) create mode 100644 cmake/config.hpp.in diff --git a/CMakeLists.txt b/CMakeLists.txt index 1ae5dff8d..91bf34434 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -89,6 +89,20 @@ if(GIT_FOUND) RESULT_VARIABLE DEPTHAI_DOWNLOADED_SOURCES OUTPUT_QUIET ERROR_QUIET ) + execute_process( + COMMAND ${GIT_EXECUTABLE} rev-parse HEAD + WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR} + OUTPUT_VARIABLE BUILD_COMMIT + ERROR_QUIET + OUTPUT_STRIP_TRAILING_WHITESPACE + ) + execute_process( + COMMAND ${GIT_EXECUTABLE} show -s --format=%ci ${BUILD_COMMIT} + WORKING_DIRECTORY ${CMAKE_CURRENT_LIST_DIR} + OUTPUT_VARIABLE BUILD_COMMIT_DATETIME + ERROR_QUIET + OUTPUT_STRIP_TRAILING_WHITESPACE + ) endif() ### Get and find dependencies @@ -162,6 +176,8 @@ add_library(${TARGET_CORE_NAME} src/bspatch/bspatch.c ) add_library("${PROJECT_NAME}::${TARGET_CORE_ALIAS}" ALIAS ${TARGET_CORE_NAME}) +# Specify that we are building core +target_compile_definitions(${TARGET_CORE_NAME} PUBLIC DEPTHAI_TARGET_CORE) # Specifies name of generated IMPORTED target (set to alias) set_target_properties(${TARGET_CORE_NAME} PROPERTIES EXPORT_NAME ${TARGET_CORE_ALIAS}) # Add to list of targets to export and install @@ -288,10 +304,6 @@ else() endif() - -# Configure build information (version, ...) -configure_file("${CMAKE_CURRENT_LIST_DIR}/cmake/version.hpp.in" "${CMAKE_CURRENT_LIST_DIR}/include/depthai/build/version.hpp") - # Add include directories target_include_directories(${TARGET_CORE_NAME} PUBLIC @@ -387,7 +399,10 @@ if(DEPTHAI_OPENCV_SUPPORT) target_link_libraries(${TARGET_OPENCV_NAME} PUBLIC ${REQUIRED_OPENCV_LIBRARIES}) # Add public compile definition indicating that OpenCV support is available - target_compile_definitions(${TARGET_OPENCV_NAME} PUBLIC DEPTHAI_OPENCV_SUPPORT) + set(DEPTHAI_HAVE_OPENCV_SUPPORT ON) + + # Specify that we are building target opencv + target_compile_definitions(${TARGET_OPENCV_NAME} PUBLIC DEPTHAI_TARGET_OPENCV) # Add public dependency to depthai::core library target_link_libraries(${TARGET_OPENCV_NAME} PUBLIC ${TARGET_CORE_NAME}) @@ -442,6 +457,17 @@ if (DEPTHAI_BUILD_DOCS) add_subdirectory(docs) endif() +######################## +# Build configuration +######################## +# Add year information +string(TIMESTAMP BUILD_DATETIME "%Y-%m-%d %H:%M:%S +0000" UTC) +message(STATUS "BUILD_DATETIME: ${BUILD_DATETIME}, BUILD_COMMIT: ${BUILD_COMMIT}, BUILD_COMMIT_DATETIME: ${BUILD_COMMIT_DATETIME}") + +# Configure build information (version, opencv support) +configure_file("${CMAKE_CURRENT_LIST_DIR}/cmake/version.hpp.in" "${CMAKE_CURRENT_LIST_DIR}/include/depthai/build/version.hpp") +configure_file("${CMAKE_CURRENT_LIST_DIR}/cmake/config.hpp.in" "${CMAKE_CURRENT_LIST_DIR}/include/depthai/build/config.hpp") + ######################## # Export and install ######################## diff --git a/cmake/config.hpp.in b/cmake/config.hpp.in new file mode 100644 index 000000000..6e1efb741 --- /dev/null +++ b/cmake/config.hpp.in @@ -0,0 +1,14 @@ +/* + * Generated by CMake build tool. + */ +#pragma once + +// This build supports OpenCV integration? +#cmakedefine DEPTHAI_HAVE_OPENCV_SUPPORT + +// Build specific settings overwrite +#ifdef DEPTHAI_TARGET_CORE +#ifndef DEPTHAI_TARGET_OPENCV +#undef DEPTHAI_HAVE_OPENCV_SUPPORT +#endif +#endif diff --git a/cmake/version.hpp.in b/cmake/version.hpp.in index 09ad2359c..292123ade 100644 --- a/cmake/version.hpp.in +++ b/cmake/version.hpp.in @@ -1,16 +1,20 @@ -/* - * Generated by CMake build tool. - * To modify version, open CMakeLists.txt and bump the version in project() function +/* + * Generated by CMake build tool. + * To modify version, open CMakeLists.txt and bump the version in project() function */ - #pragma once + namespace dai { - namespace build - { - constexpr static const char* VERSION = "${PROJECT_VERSION}"; - constexpr static const int VERSION_MAJOR = ${PROJECT_VERSION_MAJOR}; - constexpr static const int VERSION_MINOR = ${PROJECT_VERSION_MINOR}; - constexpr static const int VERSION_PATCH = ${PROJECT_VERSION_PATCH}; - } // namespace Build +namespace build +{ + constexpr static const char* VERSION = "${PROJECT_VERSION}"; + constexpr static const int VERSION_MAJOR = ${PROJECT_VERSION_MAJOR}; + constexpr static const int VERSION_MINOR = ${PROJECT_VERSION_MINOR}; + constexpr static const int VERSION_PATCH = ${PROJECT_VERSION_PATCH}; + + constexpr static const char* COMMIT = "${BUILD_COMMIT}"; + constexpr static const char* COMMIT_DATETIME = "${BUILD_COMMIT_DATETIME}"; + constexpr static const char* BUILD_DATETIME = "${BUILD_DATETIME}"; +} // namespace build } // namespace dai diff --git a/docs/Doxyfile.in b/docs/Doxyfile.in index 46a96dffb..255609576 100644 --- a/docs/Doxyfile.in +++ b/docs/Doxyfile.in @@ -2199,7 +2199,7 @@ INCLUDE_FILE_PATTERNS = # recursively expanded use the := operator instead of the = operator. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -PREDEFINED = DEPTHAI_OPENCV_SUPPORT +PREDEFINED = DEPTHAI_HAVE_OPENCV_SUPPORT # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this # tag can be used to specify a list of macro names that should be expanded. The diff --git a/include/depthai/pipeline/datatype/ImgFrame.hpp b/include/depthai/pipeline/datatype/ImgFrame.hpp index 90d830512..31ac250f3 100644 --- a/include/depthai/pipeline/datatype/ImgFrame.hpp +++ b/include/depthai/pipeline/datatype/ImgFrame.hpp @@ -4,11 +4,15 @@ #include #include -#include "depthai-shared/datatype/RawImgFrame.hpp" +// project +#include "depthai/build/config.hpp" #include "depthai/pipeline/datatype/Buffer.hpp" +// shared +#include "depthai-shared/datatype/RawImgFrame.hpp" + // optional -#ifdef DEPTHAI_OPENCV_SUPPORT +#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT #include #endif @@ -117,9 +121,9 @@ class ImgFrame : public Buffer { void setType(Type type); // Optional - OpenCV support -#ifdef DEPTHAI_OPENCV_SUPPORT +#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT /** - * @note This API only available if OpenCV support enabled + * @note This API only available if OpenCV support is enabled * * Copies cv::Mat data to ImgFrame buffer * @@ -128,7 +132,7 @@ class ImgFrame : public Buffer { void setFrame(cv::Mat frame); /** - * @note This API only available if OpenCV support enabled + * @note This API only available if OpenCV support is enabled * * Retrieves data as cv::Mat with specified width, height and type * @@ -138,7 +142,7 @@ class ImgFrame : public Buffer { cv::Mat getFrame(bool copy = false); /** - * @note This API only available if OpenCV support enabled + * @note This API only available if OpenCV support is enabled * * Retrieves cv::Mat suitable for use in common opencv functions. * ImgFrame is converted to color BGR interleaved or grayscale depending on type. @@ -148,6 +152,26 @@ class ImgFrame : public Buffer { * @returns cv::Mat for use in opencv functions */ cv::Mat getCvFrame(); + +#else + + template + struct dependent_false { + static constexpr bool value = false; + }; + template + void setFrame(T...) { + static_assert(dependent_false::value, "Library not configured with OpenCV support"); + } + template + void getFrame(T...) { + static_assert(dependent_false::value, "Library not configured with OpenCV support"); + } + template + void getCvFrame(T...) { + static_assert(dependent_false::value, "Library not configured with OpenCV support"); + } + #endif }; diff --git a/include/depthai/utility/Initialization.hpp b/include/depthai/utility/Initialization.hpp index 7a0bfab32..348d7f34a 100644 --- a/include/depthai/utility/Initialization.hpp +++ b/include/depthai/utility/Initialization.hpp @@ -1,7 +1,9 @@ #pragma once +#include + namespace dai { -bool initialize(); +bool initialize(std::string additionalInfo = ""); } // namespace dai diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index cad533c43..0216f2384 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -1,6 +1,7 @@ #include "utility/Initialization.hpp" // project +#include "build/version.hpp" #include "utility/Resources.hpp" // libraries @@ -28,7 +29,7 @@ namespace { } // namespace -bool initialize() { +bool initialize(std::string additionalInfo) { // atomic bool for checking whether depthai was already initialized static std::atomic initialized{false}; @@ -50,6 +51,13 @@ bool initialize() { // // TODO(themarpe) - instruct Device class that first available device is also a booted device // } + // Print core commit and build datetime + if(!additionalInfo.empty()) { + spdlog::debug("{}", additionalInfo); + } + spdlog::debug( + "Library information - version: {}, commit: {} from {}, build: {}", build::VERSION, build::COMMIT, build::COMMIT_DATETIME, build::BUILD_DATETIME); + // Executed at library load time // Preload Resources (getting instance causes some internal lazy loading to start) diff --git a/tests/integration/src/main.cpp b/tests/integration/src/main.cpp index bd845658f..af12ba6f4 100644 --- a/tests/integration/src/main.cpp +++ b/tests/integration/src/main.cpp @@ -12,7 +12,7 @@ int main(){ frame.setHeight(2); frame.setType(dai::ImgFrame::Type::GRAY8); -#ifdef DEPTHAI_OPENCV_SUPPORT +#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT auto x = frame.getFrame(); std::cout << "Frame cols: " << x.cols << " rows: " << x.rows << std::endl; #else From f1c14752eda267975c8aacfb99f40a08c64d3dd2 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Mon, 3 May 2021 02:06:52 +0200 Subject: [PATCH 48/53] Fixed documentation issue and inconsistencies --- include/depthai/device/DataQueue.hpp | 26 ++--- include/depthai/device/Device.hpp | 144 +++++++++++++-------------- include/depthai/pipeline/Node.hpp | 4 +- 3 files changed, 87 insertions(+), 87 deletions(-) diff --git a/include/depthai/device/DataQueue.hpp b/include/depthai/device/DataQueue.hpp index dc296d1a6..4a362b454 100644 --- a/include/depthai/device/DataQueue.hpp +++ b/include/depthai/device/DataQueue.hpp @@ -50,7 +50,7 @@ class DataOutputQueue { /** * Gets current queue behavior when full (maxSize) * - * @return true if blocking, false otherwise + * @returns True if blocking, false otherwise */ bool getBlocking() const; @@ -64,14 +64,14 @@ class DataOutputQueue { /** * Gets queue maximum size * - * @return Maximum queue size + * @returns Maximum queue size */ unsigned int getMaxSize(unsigned int maxSize) const; /** * Gets queues name * - * @return Queue name + * @returns Queue name */ std::string getName() const; @@ -79,7 +79,7 @@ class DataOutputQueue { * Adds a callback on message received * * @param callback Callback function with queue name and message pointer - * @return Callback id + * @returns Callback id */ CallbackId addCallback(std::function)>); @@ -87,7 +87,7 @@ class DataOutputQueue { * Adds a callback on message received * * @param callback Callback function with message pointer - * @return Callback id + * @returns Callback id */ CallbackId addCallback(std::function)>); @@ -95,7 +95,7 @@ class DataOutputQueue { * Adds a callback on message received * * @param callback Callback function without any parameters - * @return Callback id + * @returns Callback id */ CallbackId addCallback(std::function callback); @@ -103,13 +103,13 @@ class DataOutputQueue { * Removes a callback * * @param callbackId Id of callback to be removed - * @return true if callback was removed, false otherwise + * @returns True if callback was removed, false otherwise */ bool removeCallback(CallbackId callbackId); /** * Check whether front of the queue has message of type T - * @returns true if queue isn't empty and the first element is of type T, false otherwise + * @returns True if queue isn't empty and the first element is of type T, false otherwise */ template bool has() { @@ -123,7 +123,7 @@ class DataOutputQueue { /** * Check whether front of the queue has a message (isn't empty) - * @returns true if queue isn't empty, false otherwise + * @returns True if queue isn't empty, false otherwise */ bool has() { if(!running) throw std::runtime_error(exceptionMessage.c_str()); @@ -349,7 +349,7 @@ class DataInputQueue { /** * Gets maximum queue size. * - * @return Maximum message size + * @returns Maximum message size */ std::size_t getMaxDataSize(); @@ -363,7 +363,7 @@ class DataInputQueue { /** * Gets current queue behavior when full (maxSize) * - * @return true if blocking, false otherwise + * @returns True if blocking, false otherwise */ bool getBlocking() const; @@ -377,14 +377,14 @@ class DataInputQueue { /** * Gets queue maximum size * - * @return Maximum queue size + * @returns Maximum queue size */ unsigned int getMaxSize(unsigned int maxSize) const; /** * Gets queues name * - * @return Queue name + * @returns Queue name */ std::string getName() const; diff --git a/include/depthai/device/Device.hpp b/include/depthai/device/Device.hpp index d95c3f036..9d575bc17 100644 --- a/include/depthai/device/Device.hpp +++ b/include/depthai/device/Device.hpp @@ -50,8 +50,8 @@ class Device { /** * Waits for any available device with a timeout * - * @param timeout - duration of time to wait for the any device - * @return a tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device + * @param timeout duration of time to wait for the any device + * @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device */ template static std::tuple getAnyAvailableDevice(std::chrono::duration timeout); @@ -59,136 +59,136 @@ class Device { /** * Gets any available device * - * @return a tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device + * @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device */ static std::tuple getAnyAvailableDevice(); /** * Gets first available device. Device can be either in XLINK_UNBOOTED or XLINK_BOOTLOADER state - * @return a tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device + * @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device */ static std::tuple getFirstAvailableDevice(); /** * Finds a device by MX ID. Example: 14442C10D13EABCE00 - * @param mxId - MyraidX ID which uniquely specifies a device - * @return a tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device + * @param mxId MyraidX ID which uniquely specifies a device + * @returns Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device */ static std::tuple getDeviceByMxId(std::string mxId); /** * Returns all connected devices - * @return vector of connected devices + * @returns Vector of connected devices */ static std::vector getAllAvailableDevices(); /** * Gets device firmware binary for a specific OpenVINO version - * @param usb2Mode - USB2 mode firmware - * @param version - Version of OpenVINO which firmware will support - * @return firmware binary + * @param usb2Mode USB2 mode firmware + * @param version Version of OpenVINO which firmware will support + * @returns Firmware binary */ static std::vector getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version = Pipeline::DEFAULT_OPENVINO_VERSION); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param pipeline - Pipeline to be executed on the device + * @param pipeline Pipeline to be executed on the device */ explicit Device(const Pipeline& pipeline); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param pipeline - Pipeline to be executed on the device - * @param usb2Mode - Boot device using USB2 mode firmware + * @param pipeline Pipeline to be executed on the device + * @param usb2Mode Boot device using USB2 mode firmware */ Device(const Pipeline& pipeline, bool usb2Mode); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param pipeline - Pipeline to be executed on the device - * @param pathToCmd - Path to custom device firmware + * @param pipeline Pipeline to be executed on the device + * @param pathToCmd Path to custom device firmware */ Device(const Pipeline& pipeline, const char* pathToCmd); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param pipeline - Pipeline to be executed on the device - * @param pathToCmd - Path to custom device firmware + * @param pipeline Pipeline to be executed on the device + * @param pathToCmd Path to custom device firmware */ Device(const Pipeline& pipeline, const std::string& pathToCmd); /** * Connects to device specified by devInfo. - * @param pipeline - Pipeline to be executed on the device - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param usb2Mode - Boot device using USB2 mode firmware + * @param pipeline Pipeline to be executed on the device + * @param devInfo DeviceInfo which specifies which device to connect to + * @param usb2Mode Boot device using USB2 mode firmware */ Device(const Pipeline& pipeline, const DeviceInfo& devInfo, bool usb2Mode = false); /** * Connects to device specified by devInfo. - * @param pipeline - Pipeline to be executed on the device - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param pathToCmd - Path to custom device firmware + * @param pipeline Pipeline to be executed on the device + * @param devInfo DeviceInfo which specifies which device to connect to + * @param pathToCmd Path to custom device firmware */ Device(const Pipeline& pipeline, const DeviceInfo& devInfo, const char* pathToCmd); /** * Connects to device specified by devInfo. - * @param pipeline - Pipeline to be executed on the device - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param usb2Mode - Path to custom device firmware + * @param pipeline Pipeline to be executed on the device + * @param devInfo DeviceInfo which specifies which device to connect to + * @param usb2Mode Path to custom device firmware */ Device(const Pipeline& pipeline, const DeviceInfo& devInfo, const std::string& pathToCmd); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param version - OpenVINO version which the device will be booted with. Default is Pipeline::DEFAULT_OPENVINO_VERSION + * @param version OpenVINO version which the device will be booted with. Default is Pipeline::DEFAULT_OPENVINO_VERSION */ explicit Device(OpenVINO::Version version = Pipeline::DEFAULT_OPENVINO_VERSION); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param version - OpenVINO version which the device will be booted with - * @param usb2Mode - Boot device using USB2 mode firmware + * @param version OpenVINO version which the device will be booted with + * @param usb2Mode Boot device using USB2 mode firmware */ Device(OpenVINO::Version version, bool usb2Mode); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param version - OpenVINO version which the device will be booted with - * @param pathToCmd - Path to custom device firmware + * @param version OpenVINO version which the device will be booted with + * @param pathToCmd Path to custom device firmware */ Device(OpenVINO::Version version, const char* pathToCmd); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. - * @param version - OpenVINO version which the device will be booted with - * @param pathToCmd - Path to custom device firmware + * @param version OpenVINO version which the device will be booted with + * @param pathToCmd Path to custom device firmware */ Device(OpenVINO::Version version, const std::string& pathToCmd); /** * Connects to device specified by devInfo. - * @param version - OpenVINO version which the device will be booted with - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param usb2Mode - Boot device using USB2 mode firmware + * @param version OpenVINO version which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to + * @param usb2Mode Boot device using USB2 mode firmware */ Device(OpenVINO::Version version, const DeviceInfo& devInfo, bool usb2Mode = false); /** * Connects to device specified by devInfo. - * @param version - OpenVINO version which the device will be booted with - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param pathToCmd - Path to custom device firmware + * @param version OpenVINO version which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to + * @param pathToCmd Path to custom device firmware */ Device(OpenVINO::Version version, const DeviceInfo& devInfo, const char* pathToCmd); /** * Connects to device specified by devInfo. - * @param version - OpenVINO version which the device will be booted with - * @param devInfo - DeviceInfo which specifies which device to connect to - * @param usb2Mode - Path to custom device firmware + * @param version OpenVINO version which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to + * @param usb2Mode Path to custom device firmware */ Device(OpenVINO::Version version, const DeviceInfo& devInfo, const std::string& pathToCmd); @@ -200,14 +200,14 @@ class Device { /** * Checks if devices pipeline is already running * - * @return true if running, false otherwise + * @returns True if running, false otherwise */ bool isPipelineRunning(); /** * Starts the execution of the devices pipeline * - * @return true if pipeline started, false otherwise + * @returns True if pipeline started, false otherwise */ [[deprecated("Device(pipeline) starts the pipeline automatically. See Device() and startPipeline(pipeline) otherwise")]] bool startPipeline(); @@ -215,7 +215,7 @@ class Device { * Starts the execution of a given pipeline * @param pipeline OpenVINO version of the pipeline must match the one which the device was booted with. * - * @return true if pipeline started, false otherwise + * @returns True if pipeline started, false otherwise */ bool startPipeline(const Pipeline& pipeline); @@ -229,7 +229,7 @@ class Device { /** * Gets current logging severity level of the device. * - * @return Logging severity level + * @returns Logging severity level */ LogLevel getLogLevel(); @@ -237,22 +237,22 @@ class Device { * Sets logging level which decides printing level to standard output. * If lower than setLogLevel, no messages will be printed * - * @param level - Standard output printing severity + * @param level Standard output printing severity */ void setLogOutputLevel(LogLevel level); /** * Gets logging level which decides printing level to standard output. * - * @return Standard output printing severity + * @returns Standard output printing severity */ LogLevel getLogOutputLevel(); /** * Add a callback for device logging. The callback will be called from a separate thread with the LogMessage being passed. * - * @param callback - Callback to call whenever a log message arrives - * @return Id which can be used to later remove the callback + * @param callback Callback to call whenever a log message arrives + * @returns Id which can be used to later remove the callback */ int addLogCallback(std::function callback); @@ -260,7 +260,7 @@ class Device { * Removes a callback * * @param callbackId Id of callback to be removed - * @return true if callback was removed, false otherwise + * @returns True if callback was removed, false otherwise */ bool removeLogCallback(int callbackId); @@ -275,7 +275,7 @@ class Device { /** * Gets current rate of system information logging ("info" severity) in Hz. * - * @return Logging rate in Hz + * @returns Logging rate in Hz */ float getSystemInformationLoggingRate(); @@ -283,7 +283,7 @@ class Device { * Gets an output queue corresponding to stream name. If it doesn't exist it throws * * @param name Queue/stream name, created by XLinkOut node - * @return Smart pointer to DataOutputQueue + * @returns Smart pointer to DataOutputQueue */ std::shared_ptr getOutputQueue(const std::string& name); @@ -293,14 +293,14 @@ class Device { * @param name Queue/stream name, set in XLinkOut node * @param maxSize Maximum number of messages in queue * @param blocking Queue behavior once full. True specifies blocking and false overwriting of oldest messages. Default: true - * @return Smart pointer to DataOutputQueue + * @returns Smart pointer to DataOutputQueue */ std::shared_ptr getOutputQueue(const std::string& name, unsigned int maxSize, bool blocking = true); /** * Get all available output queue names * - * @return Vector of output queue names + * @returns Vector of output queue names */ std::vector getOutputQueueNames() const; @@ -308,7 +308,7 @@ class Device { * Gets an input queue corresponding to stream name. If it doesn't exist it throws * * @param name Queue/stream name, set in XLinkIn node - * @return Smart pointer to DataInputQueue + * @returns Smart pointer to DataInputQueue */ std::shared_ptr getInputQueue(const std::string& name); @@ -318,14 +318,14 @@ class Device { * @param name Queue/stream name, set in XLinkOut node * @param maxSize Maximum number of messages in queue * @param blocking Queue behavior once full. True: blocking, false: overwriting of oldest messages. Default: true - * @return Smart pointer to DataInputQueue + * @returns Smart pointer to DataInputQueue */ std::shared_ptr getInputQueue(const std::string& name, unsigned int maxSize, bool blocking = true); /** * Get all available input queue names * - * @return Vector of input queue names + * @returns Vector of input queue names */ std::vector getInputQueueNames() const; @@ -337,7 +337,7 @@ class Device { * @param queueNames Names of queues for which to block * @param maxNumEvents Maximum number of events to remove from queue - Default is unlimited * @param timeout Timeout after which return regardless. If negative then wait is indefinite - Default is -1 - * @return Names of queues which received messages first + * @returns Names of queues which received messages first */ std::vector getQueueEvents(const std::vector& queueNames, std::size_t maxNumEvents = std::numeric_limits::max(), @@ -352,7 +352,7 @@ class Device { * @param queueName Name of queues for which to wait for * @param maxNumEvents Maximum number of events to remove from queue. Default is unlimited * @param timeout Timeout after which return regardless. If negative then wait is indefinite. Default is -1 - * @return Names of queues which received messages first + * @returns Names of queues which received messages first */ std::vector getQueueEvents(std::string queueName, std::size_t maxNumEvents = std::numeric_limits::max(), @@ -363,7 +363,7 @@ class Device { * * @param maxNumEvents Maximum number of events to remove from queue. Default is unlimited * @param timeout Timeout after which return regardless. If negative then wait is indefinite. Default is -1 - * @return Names of queues which received messages first + * @returns Names of queues which received messages first */ std::vector getQueueEvents(std::size_t maxNumEvents = std::numeric_limits::max(), std::chrono::microseconds timeout = std::chrono::microseconds(-1)); @@ -373,7 +373,7 @@ class Device { * * @param queueNames Names of queues for which to wait for * @param timeout Timeout after which return regardless. If negative then wait is indefinite. Default is -1 - * @return Queue name which received a message first + * @returns Queue name which received a message first */ std::string getQueueEvent(const std::vector& queueNames, std::chrono::microseconds timeout = std::chrono::microseconds(-1)); std::string getQueueEvent(const std::initializer_list& queueNames, std::chrono::microseconds timeout = std::chrono::microseconds(-1)); @@ -383,7 +383,7 @@ class Device { * * @param queueNames Name of queues for which to wait for * @param timeout Timeout after which return regardless. If negative then wait is indefinite. Default is -1 - * @return Queue name which received a message + * @returns Queue name which received a message */ std::string getQueueEvent(std::string queueName, std::chrono::microseconds timeout = std::chrono::microseconds(-1)); @@ -391,63 +391,63 @@ class Device { * Gets or waits until any queue has received a message * * @param timeout Timeout after which return regardless. If negative then wait is indefinite. Default is -1 - * @return Queue name which received a message + * @returns Queue name which received a message */ std::string getQueueEvent(std::chrono::microseconds timeout = std::chrono::microseconds(-1)); /** * Get cameras that are connected to the device * - * @return Vector of connected cameras + * @returns Vector of connected cameras */ std::vector getConnectedCameras(); /** * Retrieves current DDR memory information from device * - * @return Used, remaining and total ddr memory + * @returns Used, remaining and total ddr memory */ MemoryInfo getDdrMemoryUsage(); /** * Retrieves current CMX memory information from device * - * @return Used, remaining and total cmx memory + * @returns Used, remaining and total cmx memory */ MemoryInfo getCmxMemoryUsage(); /** * Retrieves current CSS Leon CPU heap information from device * - * @return Used, remaining and total heap memory + * @returns Used, remaining and total heap memory */ MemoryInfo getLeonCssHeapUsage(); /** * Retrieves current MSS Leon CPU heap information from device * - * @return Used, remaining and total heap memory + * @returns Used, remaining and total heap memory */ MemoryInfo getLeonMssHeapUsage(); /** * Retrieves current chip temperature as measured by device * - * @return Temperature of various onboard sensors + * @returns Temperature of various onboard sensors */ ChipTemperature getChipTemperature(); /** * Retrieves average CSS Leon CPU usage * - * @return Average CPU usage and sampling duration + * @returns Average CPU usage and sampling duration */ CpuUsage getLeonCssCpuUsage(); /** * Retrieves average MSS Leon CPU usage * - * @return Average CPU usage and sampling duration + * @returns Average CPU usage and sampling duration */ CpuUsage getLeonMssCpuUsage(); diff --git a/include/depthai/pipeline/Node.hpp b/include/depthai/pipeline/Node.hpp index 137669743..b9784b861 100644 --- a/include/depthai/pipeline/Node.hpp +++ b/include/depthai/pipeline/Node.hpp @@ -117,7 +117,7 @@ class Node { /** * Get input queue behavior - * @return True blocking, false overwriting + * @returns True blocking, false overwriting */ bool getBlocking() const; @@ -130,7 +130,7 @@ class Node { /** * Get input queue size. - * @return Maximum input queue size + * @returns Maximum input queue size */ int getQueueSize() const; }; From 3d710e36df879f2a6ccd4375fa680786d3410644 Mon Sep 17 00:00:00 2001 From: SzabolcsGergely Date: Mon, 3 May 2021 15:32:30 +0300 Subject: [PATCH 49/53] Update depthai-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 e7cc3ea6e..c1a311025 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 "0fb718d9fd3f9e183a0ca0136bee3f50439c96e7") +set(DEPTHAI_DEVICE_SIDE_COMMIT "59c6e4cc56a0cfc1342dadd525458f4ff41ddb06") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/shared/depthai-shared b/shared/depthai-shared index 2de168a74..c347a77dd 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 2de168a74d97d3f1479d96824a630c12e87ca16a +Subproject commit c347a77dde101e8775fab754b24b7212cbed47d4 From 75038999b6766ffede481b3e40c8e16a956153cd Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 3 May 2021 17:03:35 +0300 Subject: [PATCH 50/53] Update FW (properly set flipping with LRcheck enabled to spatial calculator), update StereoDepth docs --- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- include/depthai/pipeline/node/StereoDepth.hpp | 19 ++++++++++++++----- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index c1a311025..cc36f7254 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 "59c6e4cc56a0cfc1342dadd525458f4ff41ddb06") +set(DEPTHAI_DEVICE_SIDE_COMMIT "16652fb049b5a9b47e3098d94fb9cedc353f82e9") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index 6c57614c7..b716d8f91 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -43,11 +43,16 @@ class StereoDepth : public Node { /** * Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in millimeters. + * + * Non-determined / invalid depth values are set to 0 */ Output depth{*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; /** - * Outputs ImgFrame message that carries RAW8 encoded (0..96 or 0..192 for Extended mode) disparity data. + * Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data: + * - RAW8 encoded (0..95) for standard mode + * - RAW8 encoded (0..190) for extended disparity mode + * - RAW16 encoded (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode) */ Output disparity{*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; @@ -121,21 +126,21 @@ class StereoDepth : public Node { /** * Computes and combines disparities in both L-R and R-L directions, and combine them. * - * For better occlusion handling + * For better occlusion handling, discarding invalid disparity values */ void setLeftRightCheck(bool enable); /** * Computes disparity with sub-pixel interpolation (5 fractional bits). * - * Suitable for long range + * Suitable for long range. Currently incompatible with extended disparity */ void setSubpixel(bool enable); /** * Disparity range increased from 0-95 to 0-190, combined from full resolution and downscaled images. * - * Suitable for short range objects + * Suitable for short range objects. Currently incompatible with sub-pixel disparity */ void setExtendedDisparity(bool enable); @@ -146,7 +151,11 @@ class StereoDepth : public Node { void setRectifyEdgeFillColor(int color); /** - * Mirror rectified frames + * Mirror rectified frames, only when LR-check mode is disabled. Default `true`. + * The mirroring is required to have a normal non-mirrored disparity/depth output. + * A side effect of this option is disparity alignment to the perspective of left or right input: + * - LR-check disabled: `false`: mapped to left and mirrored, `true`: mapped to right; + * - LR-check enabled: `false`: mapped to right, `true`: mapped to left, never mirrored. * @param enable True for normal disparity/depth, otherwise mirrored */ void setRectifyMirrorFrame(bool enable); From 845b3f7d7dd196b0d4da30234d5872a9e4eee36d Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 3 May 2021 17:31:26 +0300 Subject: [PATCH 51/53] Try fixing docs build: docstring of depthai.StereoDepth.disparity:6: WARNING: Bullet list ends without a blank line; unexpected unindent. --- include/depthai/pipeline/node/StereoDepth.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index b716d8f91..ee9e2f3e7 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -53,6 +53,7 @@ class StereoDepth : public Node { * - RAW8 encoded (0..95) for standard mode * - RAW8 encoded (0..190) for extended disparity mode * - RAW16 encoded (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode) + * */ Output disparity{*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; @@ -153,9 +154,11 @@ class StereoDepth : public Node { /** * Mirror rectified frames, only when LR-check mode is disabled. Default `true`. * The mirroring is required to have a normal non-mirrored disparity/depth output. + * * A side effect of this option is disparity alignment to the perspective of left or right input: * - LR-check disabled: `false`: mapped to left and mirrored, `true`: mapped to right; * - LR-check enabled: `false`: mapped to right, `true`: mapped to left, never mirrored. + * * @param enable True for normal disparity/depth, otherwise mirrored */ void setRectifyMirrorFrame(bool enable); From f849f03e57e5ab4ff3c9dd9c3cceeef9577bf74f Mon Sep 17 00:00:00 2001 From: alex-luxonis Date: Mon, 3 May 2021 18:03:29 +0300 Subject: [PATCH 52/53] Fix docs build --- include/depthai/pipeline/node/StereoDepth.hpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index ee9e2f3e7..b45503d11 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -50,10 +50,9 @@ class StereoDepth : public Node { /** * Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data: - * - RAW8 encoded (0..95) for standard mode - * - RAW8 encoded (0..190) for extended disparity mode - * - RAW16 encoded (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode) - * + * RAW8 encoded (0..95) for standard mode; + * RAW8 encoded (0..190) for extended disparity mode; + * RAW16 encoded (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode). */ Output disparity{*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}; From dd151418f2f4756cd5dcad0e7847acbdab5dbf72 Mon Sep 17 00:00:00 2001 From: TheMarpe Date: Tue, 4 May 2021 15:28:20 +0200 Subject: [PATCH 53/53] Bump version to 2.3.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 91bf34434..ea0ae3be7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,7 +26,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.2.1" LANGUAGES CXX C) +project(depthai VERSION "2.3.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)