From ef1481fc2c76740dffb311e8a69bd13095bd2b0d Mon Sep 17 00:00:00 2001 From: Adam Serafin Date: Wed, 21 Aug 2024 12:55:53 +0200 Subject: [PATCH] Ros release 2.28.0 (#1106) --- .github/workflows/main.workflow.yml | 6 +- .github/workflows/python-main.yml | 5 + CHANGELOG.rst | 18 + CMakeLists.txt | 38 +- README.md | 12 +- cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- cmake/Hunter/config.cmake | 41 ++- cmake/depthaiConfig.cmake.in | 2 + cmake/depthaiDependencies.cmake | 12 + examples/CMakeLists.txt | 15 +- examples/Cast/cast_blur.cpp | 50 +++ examples/Cast/cast_concat.cpp | 63 ++++ examples/Cast/cast_diff.cpp | 66 ++++ examples/ImageAlign/image_align.cpp | 12 +- include/depthai/device/DeviceBase.hpp | 4 + include/depthai/pipeline/node/Camera.hpp | 2 +- include/depthai/pipeline/node/ColorCamera.hpp | 2 +- include/depthai/pipeline/node/MonoCamera.hpp | 2 +- package.xml | 2 +- shared/depthai-shared | 2 +- src/device/DataQueue.cpp | 1 + src/device/DeviceBase.cpp | 28 +- src/pipeline/datatype/StreamMessageParser.cpp | 1 + src/utility/LogCollection.cpp | 238 +++++++++++++ src/utility/LogCollection.hpp | 13 + src/utility/sha1.hpp | 335 ++++++++++++++++++ src/utility/spdlog-fmt.hpp | 19 + 27 files changed, 938 insertions(+), 53 deletions(-) create mode 100644 .github/workflows/python-main.yml create mode 100644 examples/Cast/cast_blur.cpp create mode 100644 examples/Cast/cast_concat.cpp create mode 100644 examples/Cast/cast_diff.cpp create mode 100644 src/utility/LogCollection.cpp create mode 100644 src/utility/LogCollection.hpp create mode 100644 src/utility/sha1.hpp diff --git a/.github/workflows/main.workflow.yml b/.github/workflows/main.workflow.yml index c8f64c125..642b3197f 100644 --- a/.github/workflows/main.workflow.yml +++ b/.github/workflows/main.workflow.yml @@ -62,8 +62,8 @@ jobs: runs-on: ${{ matrix.os }} strategy: matrix: - os: [macos-11, windows-latest, ubuntu-latest] - cmake: ['3.10.x', ''] # Older version (Ubuntu 18.04) and newest + os: [macos-latest, windows-latest, ubuntu-latest] + cmake: ['3.10.x', '3.29.x'] # Older version (Ubuntu 18.04) and newest exclude: - os: windows-latest cmake: '3.10.x' @@ -185,6 +185,8 @@ jobs: - name: Setup cmake uses: jwlawson/actions-setup-cmake@v1.13 + with: + cmake-version: '3.29.x' - name: Configure ${{ matrix.build-type }}, shared ${{ matrix.shared }}, ${{ matrix.platform }} run: cmake -S . -B build -D BUILD_SHARED_LIBS=${{ matrix.shared}} -D CMAKE_BUILD_TYPE=${{ matrix.build-type }} -D CMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/depthai_install ${{ env.CMAKE_ARGS }} diff --git a/.github/workflows/python-main.yml b/.github/workflows/python-main.yml new file mode 100644 index 000000000..257af235c --- /dev/null +++ b/.github/workflows/python-main.yml @@ -0,0 +1,5 @@ +name: Depthai Python CI/CD + +# Added to main to allow workflow_dispath on v3 branches +on: + workflow_dispatch: \ No newline at end of file diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 81145e4d5..afa13dd18 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,6 +1,24 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package depthai ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.28.0 (2024-08-21) +----------- +Features +* Changed the automatic crashdump collection to always on unless DEPTHAI_DISABLE_CRASHDUMP_COLLECTION is set. +* Added DEPTHAI_ENABLE_ANALYTICS_COLLECTION environment varialbe - when set, analytic data (pipeline schema) is sent to Luxonis which will be used to further improve the library. +* Undistort both outputs of ToF by default. +* Improved 3A syncing on OAK-D-LR +* Added support for YoloV10 +* Bug fixes +* Fix Camera node to correctly allocate resources for undistortion +* Fix StereoDepth node when decimation filter and depth alignment are used +* Fix host timestamps of thermal frames to be synced +* Misc +* Updated XLink to support clangd and shared libraries on Windows: +* luxonis/XLink#81 +* luxonis/XLink#84 +* Remove a custom assert to always produce a crash dump to improve the UX with the automatic crashdump collection +* Increased watchdog priority on device side to improve stability during high load 2.26.1 (2024-06-12) ----------- diff --git a/CMakeLists.txt b/CMakeLists.txt index 9594a4755..be08685d7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -13,6 +13,18 @@ set(CMAKE_POSITION_INDEPENDENT_CODE ON) # Early options option(DEPTHAI_ENABLE_LIBUSB "Enable usage of libusb and interaction with USB devices" ON) +# Early options +option(DEPTHAI_ENABLE_LIBUSB "Enable usage of libusb and interaction with USB devices" ON) + +# Set to use native tls for windows before including Hunter (used for Curl) +if(WIN32) + set(DEPTHAI_CURL_USE_SCHANNEL ON) + set(DEPTHAI_CURL_USE_OPENSSL OFF) +else() + set(DEPTHAI_CURL_USE_SCHANNEL OFF) + set(DEPTHAI_CURL_USE_OPENSSL ON) +endif() + # Set type to canonicalize relative paths for user-provided toolchain set(CMAKE_TOOLCHAIN_FILE "" CACHE FILEPATH "CMake toolchain path") @@ -39,8 +51,8 @@ endif() include("cmake/HunterGate.cmake") HunterGate( - URL "https://github.com/cpp-pm/hunter/archive/v0.23.322.tar.gz" - SHA1 "cb0ea1f74f4a2c49a807de34885743495fccccbe" + URL "https://github.com/cpp-pm/hunter/archive/9d9242b60d5236269f894efd3ddd60a9ca83dd7f.tar.gz" + SHA1 "16cc954aa723bccd16ea45fc91a858d0c5246376" LOCAL # Local config for dependencies ) @@ -50,7 +62,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.26.1" LANGUAGES CXX C) +project(depthai VERSION "2.28.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) @@ -115,6 +127,16 @@ else() endif() endif() +# Check if on 32 bit linux - default without CURL support +if(CMAKE_SIZEOF_VOID_P EQUAL 4 AND UNIX) + set(DEPTHAI_DEFAULT_CURL_SUPPORT OFF) +else() + set(DEPTHAI_DEFAULT_CURL_SUPPORT ON) +endif() + +option(DEPTHAI_ENABLE_CURL "Enable CURL support" ${DEPTHAI_DEFAULT_CURL_SUPPORT}) +message(STATUS "CURL support: ${DEPTHAI_ENABLE_CURL}") + # Force Colored output when using Ninja # Global option - affects all targets option(FORCE_COLORED_OUTPUT "Always produce ANSI-colored output (GNU/Clang only)" OFF) @@ -271,6 +293,7 @@ add_library(${TARGET_CORE_NAME} src/utility/XLinkGlobalProfilingLogger.cpp src/utility/Logging.cpp src/utility/EepromDataParser.cpp + src/utility/LogCollection.cpp src/xlink/XLinkConnection.cpp src/xlink/XLinkStream.cpp src/openvino/OpenVINO.cpp @@ -461,8 +484,17 @@ target_link_libraries(${TARGET_CORE_NAME} archive_static spdlog::spdlog ZLIB::zlib + ghcFilesystem::ghc_filesystem ) +if(DEPTHAI_ENABLE_CURL) + target_link_libraries(${TARGET_CORE_NAME} PRIVATE + CURL::libcurl + cpr::cpr + ) + target_compile_definitions(${TARGET_CORE_NAME} PRIVATE DEPTHAI_ENABLE_CURL) +endif() + # Add compile & CMake definitions set(DEPTHAI_DEVICE_VERSION "${DEPTHAI_DEVICE_SIDE_COMMIT}") target_compile_definitions(${TARGET_CORE_NAME} diff --git a/README.md b/README.md index cfc74f3d9..c30bd1a2f 100644 --- a/README.md +++ b/README.md @@ -27,6 +27,15 @@ To install PCL: MacOS: `brew install pcl` Linux: `sudo apt install libpcl-dev` +> ℹ️ On Linux distributions based on RPMs, you need to install `perl-core` required by OpenSSL dependency. +>``` +>sudo yum install perl-core +>``` +> +> Another option is to disable CURL support by setting `DEPTHAI_ENABLE_CURL=OFF` when configuring CMake. +> ``` +> cmake -S. -Bbuild -D'DEPTHAI_ENABLE_CURL=OFF' +> ``` ## Building Make sure submodules are updated @@ -194,7 +203,8 @@ The following environment variables can be set to alter default behavior of the | DEPTHAI_LIBUSB_ANDROID_JAVAVM | JavaVM pointer that is passed to libusb for rootless Android interaction with devices. Interpreted as decimal value of uintptr_t | | DEPTHAI_CRASHDUMP | Directory in which to save the crash dump. | | DEPTHAI_CRASHDUMP_TIMEOUT | Specifies the duration in seconds to wait for device reboot when obtaining a crash dump. Crash dump retrieval disabled if 0. | -| DEPTHAI_PCL_SUPPORT | Enables PCL support. | +| DEPTHAI_ENABLE_ANALYTICS_COLLECTION | Enables automatic analytics collection (pipeline schemas) used to improve the library | +| DEPTHAI_DISABLE_CRASHDUMP_COLLECTION | Disables automatic crash dump collection used to improve the library | ## Running tests diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index ddf90cb8b..a493b37d6 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 "24a3b465b979de3f69410cd225914d8bd029f3ba") +set(DEPTHAI_DEVICE_SIDE_COMMIT "9ed7c9ae4c232ff93a3500a585a6b1c00650e22c") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 6a7a85458..56c59a4f0 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -1,15 +1,13 @@ hunter_config( nlohmann_json VERSION "3.9.1" - URL "https://github.com/nlohmann/json/archive/v3.9.1.tar.gz" - SHA1 "f8a20a7e19227906d77de0ede97468fbcfea03e7" ) hunter_config( XLink - VERSION "luxonis-2021.4.2-xlink-linkid-race-fix" - URL "https://github.com/luxonis/XLink/archive/e9eb1ef38030176ad70cddd3b545d5e6c509f1e1.tar.gz" - SHA1 "b1e4ded41cd7b9c37189468e2aaddbb10cbda9f6" + VERSION "luxonis-2021.4.2-master" + URL "https://github.com/luxonis/XLink/archive/2b517e1cb1ca77bea17679f9fdeb739812431174.tar.gz" + SHA1 "fa7eeb46abeb97626dad923b7733899198284587" CMAKE_ARGS XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB} ) @@ -126,3 +124,36 @@ hunter_config( # Build shared libs by default to not cause licensing issues BUILD_SHARED_LIBS=ON ) + +hunter_config( + CURL + VERSION "7.88.1-p0-custom" + URL "https://github.com/cpp-pm/curl/archive/25d45e89d140d6ab27103cd7f8f6d7d6cf548d47.tar.gz" + SHA1 "db96d87e078e529a90dfb74de8d360a785c053aa" + CMAKE_ARGS + BUILD_CURL_TESTS=OFF + BUILD_CURL_EXE=OFF + CURL_USE_SCHANNEL=${DEPTHAI_CURL_USE_SCHANNEL} + CURL_USE_OPENSSL=${DEPTHAI_CURL_USE_OPENSSL} # Override hunter flags - no OpenSSL needed on Windows + BUILD_STATIC_CURL=ON + BUILD_SHARED_LIBS=OFF + BUILD_STATIC_LIBS=ON +) + +# A hunterized and patched version of cpr- see https://github.com/luxonis/cpr/pull/1 +hunter_config( + cpr + VERSION "1.4.0" + URL "https://github.com/luxonis/cpr/archive/50a1321738554e0152b0a6f1b0ca24e4fdecff5c.tar.gz" + SHA1 "2e2ba9920ed99c19887592ca89d9be5ffce4722b" +) + +hunter_config( + ghc_filesystem + VERSION "1.5.14-luxonis" + URL "https://github.com/luxonis/filesystem/archive/d29630953f3526b61842d937764f012503a79ec3.tar.gz" + SHA1 "1cee5c95b53e014710970c920230ad1d3f3b5055" + CMAKE_ARGS + GHC_FILESYSTEM_BUILD_EXAMPLES=OFF + GHC_FILESYSTEM_BUILD_TESTING=OFF +) diff --git a/cmake/depthaiConfig.cmake.in b/cmake/depthaiConfig.cmake.in index 98309545b..0c7d60332 100644 --- a/cmake/depthaiConfig.cmake.in +++ b/cmake/depthaiConfig.cmake.in @@ -4,6 +4,8 @@ set(DEPTHAI_SHARED_LIBS @BUILD_SHARED_LIBS@) # Get whether library was build with Backward or not set(DEPTHAI_ENABLE_BACKWARD @DEPTHAI_ENABLE_BACKWARD@) +set(DEPTHAI_ENABLE_CURL @DEPTHAI_ENABLE_CURL@) + # Specify that this is config mode (Called by find_package) set(CONFIG_MODE TRUE) diff --git a/cmake/depthaiDependencies.cmake b/cmake/depthaiDependencies.cmake index 771cffbdb..d6bb55735 100644 --- a/cmake/depthaiDependencies.cmake +++ b/cmake/depthaiDependencies.cmake @@ -29,6 +29,12 @@ else() if(DEPTHAI_PCL_SUPPORT) hunter_add_package(jsoncpp) endif() + + if(DEPTHAI_ENABLE_CURL) + hunter_add_package(CURL) + hunter_add_package(cpr) + endif() + hunter_add_package(ghc_filesystem) endif() # If library was build as static, find all dependencies @@ -58,6 +64,12 @@ if(NOT CONFIG_MODE OR (CONFIG_MODE AND NOT DEPTHAI_SHARED_LIBS)) unset(STACK_DETAILS_AUTO_DETECT) endif() + # Log collection dependencies + if(DEPTHAI_ENABLE_CURL) + find_package(CURL ${_QUIET} CONFIG REQUIRED) + find_package(cpr ${_QUIET} CONFIG REQUIRED) + endif() + find_package(ghc_filesystem ${_QUIET} CONFIG REQUIRED) endif() # Add threads (c++) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f3c0762b8..f1455eabd 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -287,7 +287,6 @@ dai_add_example(rgb_encoding_mono_mobilenet mixed/rgb_encoding_mono_mobilenet.cp dai_add_example(rgb_encoding_mono_mobilenet_depth mixed/rgb_encoding_mono_mobilenet_depth.cpp ON OFF) dai_add_example(rgb_encoding_mobilenet mixed/rgb_encoding_mobilenet.cpp ON OFF) dai_add_example(multiple_devices mixed/multiple_devices.cpp OFF OFF) -dai_add_example(frame_sync mixed/frame_sync.cpp ON OFF) target_compile_definitions(mono_depth_mobilenetssd PRIVATE BLOB_PATH="${mobilenet_blob}") target_compile_definitions(rgb_encoding_mono_mobilenet PRIVATE BLOB_PATH="${mobilenet_blob}") @@ -410,15 +409,15 @@ dai_add_example(thermal_align ImageAlign/thermal_align.cpp OFF OFF) dai_add_example(depth_align ImageAlign/depth_align.cpp ON OFF) # Cast -dai_add_example(blur Cast/blur.cpp ON OFF) -target_compile_definitions(blur PRIVATE BLOB_PATH="${blur_model}") -dai_add_example(concat Cast/concat.cpp ON OFF) -target_compile_definitions(concat PRIVATE BLOB_PATH="${concat_model}") -dai_add_example(diff Cast/diff.cpp ON OFF) -target_compile_definitions(diff PRIVATE BLOB_PATH="${diff_model}") +dai_add_example(cast_blur Cast/cast_blur.cpp ON OFF) +target_compile_definitions(cast_blur PRIVATE BLOB_PATH="${blur_model}") +dai_add_example(cast_concat Cast/cast_concat.cpp ON OFF) +target_compile_definitions(cast_concat PRIVATE BLOB_PATH="${concat_model}") +dai_add_example(cast_diff Cast/cast_diff.cpp ON OFF) +target_compile_definitions(cast_diff PRIVATE BLOB_PATH="${diff_model}") + # ToF dai_add_example(spatial_tiny_yolo_tof_v3 SpatialDetection/spatial_tiny_yolo_tof.cpp OFF OFF) dai_add_example(spatial_tiny_yolo_tof_v4 SpatialDetection/spatial_tiny_yolo_tof.cpp OFF OFF) target_compile_definitions(spatial_tiny_yolo_tof_v3 PRIVATE BLOB_PATH="${tiny_yolo_v3_blob}") -target_compile_definitions(spatial_tiny_yolo_tof_v4 PRIVATE BLOB_PATH="${tiny_yolo_v4_blob}") \ No newline at end of file diff --git a/examples/Cast/cast_blur.cpp b/examples/Cast/cast_blur.cpp new file mode 100644 index 000000000..8c762a2d0 --- /dev/null +++ b/examples/Cast/cast_blur.cpp @@ -0,0 +1,50 @@ +#include +#include + +constexpr int SHAPE = 300; + +int main() { + dai::Pipeline p; + + auto camRgb = p.create(); + auto nn = p.create(); + auto rgbOut = p.create(); + auto cast = p.create(); + auto castXout = p.create(); + + camRgb->setPreviewSize(SHAPE, SHAPE); + camRgb->setInterleaved(false); + + nn->setBlobPath(BLOB_PATH); + + rgbOut->setStreamName("rgb"); + castXout->setStreamName("cast"); + + cast->setOutputFrameType(dai::ImgFrame::Type::BGR888p); + + // Linking + camRgb->preview.link(nn->input); + camRgb->preview.link(rgbOut->input); + nn->out.link(cast->input); + cast->output.link(castXout->input); + + dai::Device device(p); + auto qCam = device.getOutputQueue("rgb", 4, false); + auto qCast = device.getOutputQueue("cast", 4, false); + + while(true) { + auto inCast = qCast->get(); + auto inRgb = qCam->get(); + + if(inCast && inRgb) { + cv::imshow("Blur", inCast->getCvFrame()); + cv::imshow("Original", inRgb->getCvFrame()); + } + + if(cv::waitKey(1) == 'q') { + break; + } + } + + return 0; +} \ No newline at end of file diff --git a/examples/Cast/cast_concat.cpp b/examples/Cast/cast_concat.cpp new file mode 100644 index 000000000..7168ac4c3 --- /dev/null +++ b/examples/Cast/cast_concat.cpp @@ -0,0 +1,63 @@ +#include +#include + +constexpr int SHAPE = 300; + +int main() { + dai::Pipeline p; + + auto camRgb = p.create(); + auto left = p.create(); + auto right = p.create(); + auto manipLeft = p.create(); + auto manipRight = p.create(); + auto nn = p.create(); + auto cast = p.create(); + auto castXout = p.create(); + + camRgb->setPreviewSize(SHAPE, SHAPE); + camRgb->setInterleaved(false); + camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); + + left->setCamera("left"); + left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + manipLeft->initialConfig.setResize(SHAPE, SHAPE); + manipLeft->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p); + + right->setCamera("right"); + right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + manipRight->initialConfig.setResize(SHAPE, SHAPE); + manipRight->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p); + + nn->setBlobPath(BLOB_PATH); + nn->setNumInferenceThreads(2); + + castXout->setStreamName("cast"); + cast->setOutputFrameType(dai::ImgFrame::Type::BGR888p); + + // Linking + left->out.link(manipLeft->inputImage); + right->out.link(manipRight->inputImage); + manipLeft->out.link(nn->inputs["img1"]); + camRgb->preview.link(nn->inputs["img2"]); + manipRight->out.link(nn->inputs["img3"]); + nn->out.link(cast->input); + cast->output.link(castXout->input); + + // Pipeline is defined, now we can connect to the device + dai::Device device(p); + auto qCast = device.getOutputQueue("cast", 4, false); + + while(true) { + auto inCast = qCast->get(); + if(inCast) { + cv::imshow("Concated frames", inCast->getCvFrame()); + } + + if(cv::waitKey(1) == 'q') { + break; + } + } + + return 0; +} \ No newline at end of file diff --git a/examples/Cast/cast_diff.cpp b/examples/Cast/cast_diff.cpp new file mode 100644 index 000000000..78960beaf --- /dev/null +++ b/examples/Cast/cast_diff.cpp @@ -0,0 +1,66 @@ +#include +#include +#include + +constexpr int SHAPE = 720; + +int main() { + dai::Pipeline p; + + auto camRgb = p.create(); + auto nn = p.create(); + auto script = p.create(); + auto rgbXout = p.create(); + auto cast = p.create(); + auto castXout = p.create(); + + camRgb->setVideoSize(SHAPE, SHAPE); + camRgb->setPreviewSize(SHAPE, SHAPE); + camRgb->setInterleaved(false); + + nn->setBlobPath(BLOB_PATH); + + script->setScript(R"( + old = node.io['in'].get() + while True: + frame = node.io['in'].get() + node.io['img1'].send(old) + node.io['img2'].send(frame) + old = frame + )"); + + rgbXout->setStreamName("rgb"); + castXout->setStreamName("cast"); + cast->setOutputFrameType(dai::RawImgFrame::Type::GRAY8); + + // Linking + camRgb->preview.link(script->inputs["in"]); + script->outputs["img1"].link(nn->inputs["img1"]); + script->outputs["img2"].link(nn->inputs["img2"]); + camRgb->video.link(rgbXout->input); + nn->out.link(cast->input); + cast->output.link(castXout->input); + + // Pipeline is defined, now we can connect to the device + dai::Device device(p); + auto qCam = device.getOutputQueue("rgb", 4, false); + auto qCast = device.getOutputQueue("cast", 4, false); + + while(true) { + auto colorFrame = qCam->get(); + if(colorFrame) { + cv::imshow("Color", colorFrame->getCvFrame()); + } + + auto inCast = qCast->get(); + if(inCast) { + cv::imshow("Diff", inCast->getCvFrame()); + } + + if(cv::waitKey(1) == 'q') { + break; + } + } + + return 0; +} \ No newline at end of file diff --git a/examples/ImageAlign/image_align.cpp b/examples/ImageAlign/image_align.cpp index a676d13a0..d824dd94e 100644 --- a/examples/ImageAlign/image_align.cpp +++ b/examples/ImageAlign/image_align.cpp @@ -8,7 +8,6 @@ constexpr auto FPS = 30.0; constexpr auto RGB_SOCKET = dai::CameraBoardSocket::CAM_A; constexpr auto LEFT_SOCKET = dai::CameraBoardSocket::CAM_B; -constexpr auto RIGHT_SOCKET = dai::CameraBoardSocket::CAM_C; constexpr auto ALIGN_SOCKET = LEFT_SOCKET; constexpr auto COLOR_RESOLUTION = dai::ColorCameraProperties::SensorResolution::THE_1080_P; @@ -35,12 +34,12 @@ class FPSCounter { }; double rgbWeight = 0.4; -double depthWeight = 0.6; +double leftWeight = 0.6; int staticDepthPlane = 0; void updateBlendWeights(int percentRgb, void*) { rgbWeight = static_cast(percentRgb) / 100.0; - depthWeight = 1.0 - rgbWeight; + leftWeight = 1.0 - rgbWeight; } void updateDepthPlane(int depth, void*) { @@ -52,7 +51,6 @@ int main() { auto camRgb = pipeline.create(); auto left = pipeline.create(); - auto right = pipeline.create(); auto sync = pipeline.create(); auto out = pipeline.create(); auto align = pipeline.create(); @@ -62,10 +60,6 @@ int main() { left->setBoardSocket(LEFT_SOCKET); left->setFps(FPS); - right->setResolution(LEFT_RIGHT_RESOLUTION); - right->setBoardSocket(RIGHT_SOCKET); - right->setFps(FPS); - camRgb->setBoardSocket(RGB_SOCKET); camRgb->setResolution(COLOR_RESOLUTION); camRgb->setFps(FPS); @@ -115,7 +109,7 @@ int main() { } cv::Mat blended; - cv::addWeighted(frameRgbCv, rgbWeight, leftCv, depthWeight, 0, blended); + cv::addWeighted(frameRgbCv, rgbWeight, leftCv, leftWeight, 0, blended); cv::imshow(windowName, blended); } diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 4d533064a..b9a9355c7 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -37,6 +37,7 @@ #include "depthai-shared/device/CrashDump.hpp" #include "depthai-shared/log/LogLevel.hpp" #include "depthai-shared/log/LogMessage.hpp" +#include "depthai-shared/pipeline/PipelineSchema.hpp" namespace dai { @@ -995,5 +996,8 @@ class DeviceBase { dai::Path firmwarePath; bool dumpOnly = false; + + // Schema of the started pipeline + tl::optional pipelineSchema; }; } // namespace dai diff --git a/include/depthai/pipeline/node/Camera.hpp b/include/depthai/pipeline/node/Camera.hpp index 0e7f2c778..de9338d18 100644 --- a/include/depthai/pipeline/node/Camera.hpp +++ b/include/depthai/pipeline/node/Camera.hpp @@ -205,7 +205,7 @@ class Camera : public NodeCRTP { * Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. */ - void setIsp3aFps(int isp3aFps); + [[deprecated("setIsp3aFps is unstable")]] void setIsp3aFps(int isp3aFps); /** * Get rate at which camera should produce frames diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 0f2890e71..fc2859f0f 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -230,7 +230,7 @@ class ColorCamera : public NodeCRTP { * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. */ - void setIsp3aFps(int isp3aFps); + [[deprecated("setIsp3aFps is unstable")]] void setIsp3aFps(int isp3aFps); // Set events on which frames will be received void setFrameEventFilter(const std::vector& events); diff --git a/include/depthai/pipeline/node/MonoCamera.hpp b/include/depthai/pipeline/node/MonoCamera.hpp index d6c6c8b52..af3ba0964 100644 --- a/include/depthai/pipeline/node/MonoCamera.hpp +++ b/include/depthai/pipeline/node/MonoCamera.hpp @@ -125,7 +125,7 @@ class MonoCamera : public NodeCRTP { * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. */ - void setIsp3aFps(int isp3aFps); + [[deprecated("setIsp3aFps is unstable")]] void setIsp3aFps(int isp3aFps); /** * Get rate at which camera should produce frames diff --git a/package.xml b/package.xml index 1a16c005b..88017ec5d 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ depthai - 2.26.1 + 2.28.0 DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform Adam Serafin diff --git a/shared/depthai-shared b/shared/depthai-shared index 9762f334f..8158fa678 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 9762f334f39fc841a5bbea9b1114bbac933710e0 +Subproject commit 8158fa678970af1b10334278dbcc544556372e9f diff --git a/src/device/DataQueue.cpp b/src/device/DataQueue.cpp index e16f2c8a1..5936b843e 100644 --- a/src/device/DataQueue.cpp +++ b/src/device/DataQueue.cpp @@ -18,6 +18,7 @@ // libraries #include "utility/Logging.hpp" +#include "utility/spdlog-fmt.hpp" // Additions #include "spdlog/fmt/bin_to_hex.h" diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 7beaf4d2f..3f81121ed 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -27,6 +27,7 @@ #include "utility/Initialization.hpp" #include "utility/PimplImpl.hpp" #include "utility/Resources.hpp" +#include "utility/spdlog-fmt.hpp" // libraries #include "XLink/XLink.h" @@ -38,6 +39,7 @@ #include "spdlog/fmt/chrono.h" #include "spdlog/sinks/stdout_color_sinks.h" #include "spdlog/spdlog.h" +#include "utility/LogCollection.hpp" #include "utility/Logging.hpp" namespace dai { @@ -527,13 +529,6 @@ unsigned int getCrashdumpTimeout(XLinkProtocol_t protocol) { return DEFAULT_CRASHDUMP_TIMEOUT + (protocol == X_LINK_TCP_IP ? device::XLINK_TCP_WATCHDOG_TIMEOUT.count() : device::XLINK_USB_WATCHDOG_TIMEOUT.count()); } -tl::optional saveCrashDump(dai::CrashDump& dump, std::string mxId) { - std::vector data; - utility::serialize(dump, data); - auto crashDumpPathStr = utility::getEnv("DEPTHAI_CRASHDUMP"); - return saveFileToTemporaryDirectory(data, mxId + "-depthai_crash_dump.json", crashDumpPathStr); -} - void DeviceBase::closeImpl() { using namespace std::chrono; auto t1 = steady_clock::now(); @@ -544,12 +539,7 @@ void DeviceBase::closeImpl() { if(hasCrashDump()) { connection->setRebootOnDestruction(true); auto dump = getCrashDump(); - auto path = saveCrashDump(dump, deviceInfo.getMxId()); - if(path.has_value()) { - pimpl->logger.warn("There was a fatal error. Crash dump saved to {}", path.value()); - } else { - pimpl->logger.warn("There was a fatal error. Crash dump could not be saved"); - } + logCollection::logCrashDump(pipelineSchema, dump, deviceInfo); } else { bool isRunning = pimpl->rpcClient->call("isRunning").as(); shouldGetCrashDump = !isRunning; @@ -607,12 +597,8 @@ void DeviceBase::closeImpl() { DeviceBase rebootingDevice(config, rebootingDeviceInfo, firmwarePath, true); if(rebootingDevice.hasCrashDump()) { auto dump = rebootingDevice.getCrashDump(); - auto path = saveCrashDump(dump, deviceInfo.getMxId()); - if(path.has_value()) { - pimpl->logger.warn("Device crashed. Crash dump saved to {}", path.value()); - } else { - pimpl->logger.warn("Device crashed. Crash dump could not be saved"); - } + logCollection::logCrashDump(pipelineSchema, dump, deviceInfo); + } else { pimpl->logger.warn("Device crashed, but no crash dump could be extracted."); } @@ -1558,6 +1544,10 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { // print assets on device side for test pimpl->rpcClient->call("printAssets"); + // Log the pipeline + logCollection::logPipeline(schema, deviceInfo); + this->pipelineSchema = schema; // Save the schema so it can be passed alongside the crashdump + // Build and start the pipeline bool success = false; std::string errorMsg; diff --git a/src/pipeline/datatype/StreamMessageParser.cpp b/src/pipeline/datatype/StreamMessageParser.cpp index 811cc62a0..f1cdcc706 100644 --- a/src/pipeline/datatype/StreamMessageParser.cpp +++ b/src/pipeline/datatype/StreamMessageParser.cpp @@ -9,6 +9,7 @@ #include #include "utility/Logging.hpp" +#include "utility/spdlog-fmt.hpp" // project #include "depthai/pipeline/datatype/ADatatype.hpp" diff --git a/src/utility/LogCollection.cpp b/src/utility/LogCollection.cpp new file mode 100644 index 000000000..44c1730be --- /dev/null +++ b/src/utility/LogCollection.cpp @@ -0,0 +1,238 @@ +#include "LogCollection.hpp" + +#include +#ifdef DEPTHAI_ENABLE_CURL + #include +#endif + +#include +#include +#include +#include +#include +#include + +#include "build/version.hpp" +#include "sha1.hpp" +#include "utility/Environment.hpp" +#include "utility/Logging.hpp" + +namespace dai { +namespace logCollection { + +constexpr auto LOG_ENDPOINT = "https://logs.luxonis.com/logs"; + +struct FileWithSHA1 { + std::string content; + std::string sha1Hash; +}; + +std::string platformToString(XLinkPlatform_t platform) { + switch(platform) { + case X_LINK_ANY_PLATFORM: + return "X_LINK_ANY_PLATFORM"; + case X_LINK_MYRIAD_X: + return "X_LINK_MYRIAD_X"; + case X_LINK_MYRIAD_2: + return "X_LINK_MYRIAD_2"; + default: + return "INVALID_ENUM_VALUE"; + } +} + +std::string protocolToString(XLinkProtocol_t protocol) { + switch(protocol) { + case X_LINK_USB_VSC: + return "X_LINK_USB_VSC"; + case X_LINK_USB_CDC: + return "X_LINK_USB_CDC"; + case X_LINK_PCIE: + return "X_LINK_PCIE"; + case X_LINK_IPC: + return "X_LINK_IPC"; + case X_LINK_TCP_IP: + return "X_LINK_TCP_IP"; + case X_LINK_NMB_OF_PROTOCOLS: + return "X_LINK_NMB_OF_PROTOCOLS"; + case X_LINK_ANY_PROTOCOL: + return "X_LINK_ANY_PROTOCOL"; + default: + return "INVALID_ENUM_VALUE"; + } +} + +std::string getOSPlatform() { +#ifdef _WIN32 + return "Windows"; +#elif __APPLE__ + return "MacOS"; +#elif __linux__ + return "Linux"; +#else + return "Other"; +#endif +} + +std::string calculateSHA1(const std::string& input) { + // We could also use SHA1 from OpenSSL and SChannel + SHA1 checksum; + checksum.update(input); + return checksum.final(); +} + +#ifdef DEPTHAI_ENABLE_CURL +bool sendLogsToServer(const tl::optional& pipelineData, const tl::optional& crashDumpData, const dai::DeviceInfo& deviceInfo) { + (void)deviceInfo; // Unused for now + // At least one of the files must be present + if(!pipelineData && !crashDumpData) { + logger::error("Incorrect usage of sendLogsToServer, at least one of the files must be present"); + return false; + } + cpr::Multipart multipart{}; + if(pipelineData) { + cpr::Buffer pipelineBuffer(pipelineData->content.begin(), pipelineData->content.end(), "pipeline.json"); + multipart.parts.emplace_back("pipelineFile", pipelineBuffer); + multipart.parts.emplace_back("pipelineId", pipelineData->sha1Hash); + } + + if(crashDumpData) { + cpr::Buffer crashDumpBuffer(crashDumpData->content.begin(), crashDumpData->content.end(), "crash_dump.json"); + multipart.parts.emplace_back("crashDumpFile", crashDumpBuffer); + multipart.parts.emplace_back("crashDumpId", crashDumpData->sha1Hash); + } + + multipart.parts.emplace_back("platform", platformToString(deviceInfo.platform)); + multipart.parts.emplace_back("connectionType", protocolToString(deviceInfo.protocol)); + multipart.parts.emplace_back("osPlatform", getOSPlatform()); + std::string daiVersion = fmt::format("{}-{}", build::VERSION, build::COMMIT); + multipart.parts.emplace_back("depthAiVersion", std::move(daiVersion)); + multipart.parts.emplace_back("productId", deviceInfo.getMxId()); + auto response = cpr::Post(cpr::Url{LOG_ENDPOINT}, multipart); + if(response.status_code != 200) { + logger::info("Failed to send logs, status code: {}", response.status_code); + return false; + } + + logger::info("Logs sent successfully"); + return true; +} +#else +bool sendLogsToServer(const tl::optional&, const tl::optional&, const dai::DeviceInfo&) { + logger::info("Not sending the logs to the server, as CURL support is disabled"); + return false; +} +#endif + +void logPipeline(const PipelineSchema& pipelineSchema, const dai::DeviceInfo& deviceInfo) { + // Check if compiled without CURL support and exit early if so +#ifndef DEPTHAI_ENABLE_CURL + (void)pipelineSchema; + (void)deviceInfo; + logger::info("Compiled without CURL support, not logging pipeline."); +#else + namespace fs = ghc::filesystem; + // Check if logging is explicitly disabled + auto loggingEnabled = utility::getEnv("DEPTHAI_ENABLE_ANALYTICS_COLLECTION"); + if(loggingEnabled.empty()) { + logger::info("Logging disabled"); + return; + } + + auto pipelineJson = nlohmann::json(pipelineSchema); + std::string pipelineJsonStr = pipelineJson.dump(); + std::string pipelineSHA1 = calculateSHA1(pipelineJsonStr); + + fs::path pipelineDir = fs::current_path() / ".cache" / "depthai" / "pipelines"; + fs::path pipelinePath = pipelineDir / pipelineSHA1 / "pipeline.json"; + + if(fs::exists(pipelinePath)) { + logger::info("Pipeline already logged"); + return; + } + + logger::info("Pipeline not logged yet, logging..."); + std::error_code ec; + fs::create_directories(pipelinePath.parent_path(), ec); + if(ec) { + logger::error("Failed to create log directory: {}", ec.message()); + return; + } + + std::ofstream pipelineFile(pipelinePath); + pipelineFile << pipelineJsonStr; + pipelineFile.close(); + + FileWithSHA1 pipelineData; + pipelineData.content = std::move(pipelineJsonStr); + pipelineData.sha1Hash = std::move(pipelineSHA1); + auto success = sendLogsToServer(pipelineData, tl::nullopt, deviceInfo); + if(!success) { + // Keep at info level to not spam in case of no internet connection + logger::info("Failed to send pipeline logs to server"); + } else { + logger::info("Pipeline logs sent to server"); + } +#endif +} + +void logCrashDump(const tl::optional& pipelineSchema, const CrashDump& crashDump, const dai::DeviceInfo& deviceInfo) { + namespace fs = ghc::filesystem; + std::string crashDumpJson = crashDump.serializeToJson().dump(); + std::string crashDumpHash = calculateSHA1(crashDumpJson); + fs::path logDir = fs::current_path() / ".cache" / "depthai" / "crashdumps"; + auto crashDumpPath = utility::getEnv("DEPTHAI_CRASHDUMP"); + fs::path crashDumpPathLocal; + if(crashDumpPath.empty()) { + crashDumpPathLocal = logDir / crashDumpHash / "crash_dump.json"; + } else { + crashDumpPathLocal = crashDumpPath; + } + auto errorString = fmt::format( + "Device with id {} has crashed. Crash dump logs are stored in: {} - please report to developers.", deviceInfo.getMxId(), crashDumpPathLocal.string()); + + std::error_code ec; + fs::create_directories(crashDumpPathLocal.parent_path(), ec); + if(ec) { + logger::error("Failed to create log directory: {}", ec.message()); + return; + } + + std::ofstream crashDumpFile(crashDumpPathLocal); + crashDumpFile << crashDumpJson; + crashDumpFile.close(); + logger::error(errorString); + // Send logs to the server if possible +#ifdef DEPTHAI_ENABLE_CURL + + FileWithSHA1 crashDumpData; + crashDumpData.content = std::move(crashDumpJson); + crashDumpData.sha1Hash = calculateSHA1(crashDumpJson); + + tl::optional pipelineData; + if(pipelineSchema) { + pipelineData = FileWithSHA1{}; + std::string pipelineJson = nlohmann::json(*pipelineSchema).dump(); + std::string pipelineSHA1 = calculateSHA1(pipelineJson); + pipelineData->content = std::move(pipelineJson); + pipelineData->sha1Hash = std::move(pipelineSHA1); + } + + // Check if logging is explicitly disabled + auto loggingDisabled = utility::getEnv("DEPTHAI_DISABLE_CRASHDUMP_COLLECTION"); + if(loggingDisabled.empty()) { + logger::info("Logging enabled"); + auto success = sendLogsToServer(pipelineData, crashDumpData, deviceInfo); + if(!success) { + // Keep at info level to not spam in case of no internet connection + logger::warn("Failed to send crash dump logs to the server."); + } + } else { + logger::info("Logging disabled"); + } +#else + (void)pipelineSchema; +#endif +} + +} // namespace logCollection +} // namespace dai diff --git a/src/utility/LogCollection.hpp b/src/utility/LogCollection.hpp new file mode 100644 index 000000000..80b5a619a --- /dev/null +++ b/src/utility/LogCollection.hpp @@ -0,0 +1,13 @@ +#pragma once + +#include +#include + +namespace dai { +namespace logCollection { + +void logPipeline(const PipelineSchema& pipelineSchema, const dai::DeviceInfo& deviceInfo); + +void logCrashDump(const tl::optional& pipelineSchema, const CrashDump& crashDump, const dai::DeviceInfo& deviceInfo); +} // namespace logCollection +} // namespace dai diff --git a/src/utility/sha1.hpp b/src/utility/sha1.hpp new file mode 100644 index 000000000..c5b460ea6 --- /dev/null +++ b/src/utility/sha1.hpp @@ -0,0 +1,335 @@ +/* + From: https://github.com/vog/sha1/blob/3f8a4aa032d144309d00dbfe972906a49b3631b9/sha1.hpp + sha1.hpp - source code of + + ============ + SHA-1 in C++ + ============ + + 100% Public Domain. + + Original C Code + -- Steve Reid + Small changes to fit into bglibs + -- Bruce Guenter + Translation to simpler C++ Code + -- Volker Diels-Grabsch + Safety fixes + -- Eugene Hopkinson + Header-only library + -- Zlatko Michailov +*/ + +#ifndef SHA1_HPP +#define SHA1_HPP + + +#include +#include +#include +#include +#include +#include + + +class SHA1 +{ +public: + SHA1(); + void update(const std::string &s); + void update(std::istream &is); + std::string final(); + static std::string from_file(const std::string &filename); + +private: + uint32_t digest[5]; + std::string buffer; + uint64_t transforms; +}; + + +static const size_t BLOCK_INTS = 16; /* number of 32bit integers per SHA1 block */ +static const size_t BLOCK_BYTES = BLOCK_INTS * 4; + + +inline static void reset(uint32_t digest[], std::string &buffer, uint64_t &transforms) +{ + /* SHA1 initialization constants */ + digest[0] = 0x67452301; + digest[1] = 0xefcdab89; + digest[2] = 0x98badcfe; + digest[3] = 0x10325476; + digest[4] = 0xc3d2e1f0; + + /* Reset counters */ + buffer = ""; + transforms = 0; +} + + +inline static uint32_t rol(const uint32_t value, const size_t bits) +{ + return (value << bits) | (value >> (32 - bits)); +} + + +inline static uint32_t blk(const uint32_t block[BLOCK_INTS], const size_t i) +{ + return rol(block[(i+13)&15] ^ block[(i+8)&15] ^ block[(i+2)&15] ^ block[i], 1); +} + + +/* + * (R0+R1), R2, R3, R4 are the different operations used in SHA1 + */ + +inline static void R0(const uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t &w, const uint32_t x, const uint32_t y, uint32_t &z, const size_t i) +{ + z += ((w&(x^y))^y) + block[i] + 0x5a827999 + rol(v, 5); + w = rol(w, 30); +} + + +inline static void R1(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t &w, const uint32_t x, const uint32_t y, uint32_t &z, const size_t i) +{ + block[i] = blk(block, i); + z += ((w&(x^y))^y) + block[i] + 0x5a827999 + rol(v, 5); + w = rol(w, 30); +} + + +inline static void R2(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t &w, const uint32_t x, const uint32_t y, uint32_t &z, const size_t i) +{ + block[i] = blk(block, i); + z += (w^x^y) + block[i] + 0x6ed9eba1 + rol(v, 5); + w = rol(w, 30); +} + + +inline static void R3(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t &w, const uint32_t x, const uint32_t y, uint32_t &z, const size_t i) +{ + block[i] = blk(block, i); + z += (((w|x)&y)|(w&x)) + block[i] + 0x8f1bbcdc + rol(v, 5); + w = rol(w, 30); +} + + +inline static void R4(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t &w, const uint32_t x, const uint32_t y, uint32_t &z, const size_t i) +{ + block[i] = blk(block, i); + z += (w^x^y) + block[i] + 0xca62c1d6 + rol(v, 5); + w = rol(w, 30); +} + + +/* + * Hash a single 512-bit block. This is the core of the algorithm. + */ + +inline static void transform(uint32_t digest[], uint32_t block[BLOCK_INTS], uint64_t &transforms) +{ + /* Copy digest[] to working vars */ + uint32_t a = digest[0]; + uint32_t b = digest[1]; + uint32_t c = digest[2]; + uint32_t d = digest[3]; + uint32_t e = digest[4]; + + /* 4 rounds of 20 operations each. Loop unrolled. */ + R0(block, a, b, c, d, e, 0); + R0(block, e, a, b, c, d, 1); + R0(block, d, e, a, b, c, 2); + R0(block, c, d, e, a, b, 3); + R0(block, b, c, d, e, a, 4); + R0(block, a, b, c, d, e, 5); + R0(block, e, a, b, c, d, 6); + R0(block, d, e, a, b, c, 7); + R0(block, c, d, e, a, b, 8); + R0(block, b, c, d, e, a, 9); + R0(block, a, b, c, d, e, 10); + R0(block, e, a, b, c, d, 11); + R0(block, d, e, a, b, c, 12); + R0(block, c, d, e, a, b, 13); + R0(block, b, c, d, e, a, 14); + R0(block, a, b, c, d, e, 15); + R1(block, e, a, b, c, d, 0); + R1(block, d, e, a, b, c, 1); + R1(block, c, d, e, a, b, 2); + R1(block, b, c, d, e, a, 3); + R2(block, a, b, c, d, e, 4); + R2(block, e, a, b, c, d, 5); + R2(block, d, e, a, b, c, 6); + R2(block, c, d, e, a, b, 7); + R2(block, b, c, d, e, a, 8); + R2(block, a, b, c, d, e, 9); + R2(block, e, a, b, c, d, 10); + R2(block, d, e, a, b, c, 11); + R2(block, c, d, e, a, b, 12); + R2(block, b, c, d, e, a, 13); + R2(block, a, b, c, d, e, 14); + R2(block, e, a, b, c, d, 15); + R2(block, d, e, a, b, c, 0); + R2(block, c, d, e, a, b, 1); + R2(block, b, c, d, e, a, 2); + R2(block, a, b, c, d, e, 3); + R2(block, e, a, b, c, d, 4); + R2(block, d, e, a, b, c, 5); + R2(block, c, d, e, a, b, 6); + R2(block, b, c, d, e, a, 7); + R3(block, a, b, c, d, e, 8); + R3(block, e, a, b, c, d, 9); + R3(block, d, e, a, b, c, 10); + R3(block, c, d, e, a, b, 11); + R3(block, b, c, d, e, a, 12); + R3(block, a, b, c, d, e, 13); + R3(block, e, a, b, c, d, 14); + R3(block, d, e, a, b, c, 15); + R3(block, c, d, e, a, b, 0); + R3(block, b, c, d, e, a, 1); + R3(block, a, b, c, d, e, 2); + R3(block, e, a, b, c, d, 3); + R3(block, d, e, a, b, c, 4); + R3(block, c, d, e, a, b, 5); + R3(block, b, c, d, e, a, 6); + R3(block, a, b, c, d, e, 7); + R3(block, e, a, b, c, d, 8); + R3(block, d, e, a, b, c, 9); + R3(block, c, d, e, a, b, 10); + R3(block, b, c, d, e, a, 11); + R4(block, a, b, c, d, e, 12); + R4(block, e, a, b, c, d, 13); + R4(block, d, e, a, b, c, 14); + R4(block, c, d, e, a, b, 15); + R4(block, b, c, d, e, a, 0); + R4(block, a, b, c, d, e, 1); + R4(block, e, a, b, c, d, 2); + R4(block, d, e, a, b, c, 3); + R4(block, c, d, e, a, b, 4); + R4(block, b, c, d, e, a, 5); + R4(block, a, b, c, d, e, 6); + R4(block, e, a, b, c, d, 7); + R4(block, d, e, a, b, c, 8); + R4(block, c, d, e, a, b, 9); + R4(block, b, c, d, e, a, 10); + R4(block, a, b, c, d, e, 11); + R4(block, e, a, b, c, d, 12); + R4(block, d, e, a, b, c, 13); + R4(block, c, d, e, a, b, 14); + R4(block, b, c, d, e, a, 15); + + /* Add the working vars back into digest[] */ + digest[0] += a; + digest[1] += b; + digest[2] += c; + digest[3] += d; + digest[4] += e; + + /* Count the number of transformations */ + transforms++; +} + + +inline static void buffer_to_block(const std::string &buffer, uint32_t block[BLOCK_INTS]) +{ + /* Convert the std::string (byte buffer) to a uint32_t array (MSB) */ + for (size_t i = 0; i < BLOCK_INTS; i++) + { + block[i] = (buffer[4*i+3] & 0xff) + | (buffer[4*i+2] & 0xff)<<8 + | (buffer[4*i+1] & 0xff)<<16 + | (buffer[4*i+0] & 0xff)<<24; + } +} + + +inline SHA1::SHA1() +{ + reset(digest, buffer, transforms); +} + + +inline void SHA1::update(const std::string &s) +{ + std::istringstream is(s); + update(is); +} + + +inline void SHA1::update(std::istream &is) +{ + while (true) + { + char sbuf[BLOCK_BYTES]; + is.read(sbuf, BLOCK_BYTES - buffer.size()); + buffer.append(sbuf, (std::size_t)is.gcount()); + if (buffer.size() != BLOCK_BYTES) + { + return; + } + uint32_t block[BLOCK_INTS]; + buffer_to_block(buffer, block); + transform(digest, block, transforms); + buffer.clear(); + } +} + + +/* + * Add padding and return the message digest. + */ + +inline std::string SHA1::final() +{ + /* Total number of hashed bits */ + uint64_t total_bits = (transforms*BLOCK_BYTES + buffer.size()) * 8; + + /* Padding */ + buffer += (char)0x80; + size_t orig_size = buffer.size(); + while (buffer.size() < BLOCK_BYTES) + { + buffer += (char)0x00; + } + + uint32_t block[BLOCK_INTS]; + buffer_to_block(buffer, block); + + if (orig_size > BLOCK_BYTES - 8) + { + transform(digest, block, transforms); + for (size_t i = 0; i < BLOCK_INTS - 2; i++) + { + block[i] = 0; + } + } + + /* Append total_bits, split this uint64_t into two uint32_t */ + block[BLOCK_INTS - 1] = (uint32_t)total_bits; + block[BLOCK_INTS - 2] = (uint32_t)(total_bits >> 32); + transform(digest, block, transforms); + + /* Hex std::string */ + std::ostringstream result; + for (size_t i = 0; i < sizeof(digest) / sizeof(digest[0]); i++) + { + result << std::hex << std::setfill('0') << std::setw(8); + result << digest[i]; + } + + /* Reset for next run */ + reset(digest, buffer, transforms); + + return result.str(); +} + + +inline std::string SHA1::from_file(const std::string &filename) +{ + std::ifstream stream(filename.c_str(), std::ios::binary); + SHA1 checksum; + checksum.update(stream); + return checksum.final(); +} + + +#endif /* SHA1_HPP */ \ No newline at end of file diff --git a/src/utility/spdlog-fmt.hpp b/src/utility/spdlog-fmt.hpp index f1d5cf2c6..4277747e6 100755 --- a/src/utility/spdlog-fmt.hpp +++ b/src/utility/spdlog-fmt.hpp @@ -4,6 +4,13 @@ #include "depthai/utility/Path.hpp" +#if FMT_VERSION >= 100000 +#include + +#include "depthai/common/CameraBoardSocket.hpp" +#include "depthai-shared/datatype/DatatypeEnum.hpp" +#endif + namespace dai { namespace utility { static constexpr char path_convert_err[] = ""; @@ -25,3 +32,15 @@ struct fmt::formatter : formatter { return formatter::format(output, ctx); } }; + +#if FMT_VERSION >= 100000 +template <> +struct fmt::formatter : ostream_formatter {}; + +template <> +struct fmt::formatter : fmt::formatter { + auto format(dai::DatatypeEnum my, format_context& ctx) const -> decltype(ctx.out()) { + return fmt::format_to(ctx.out(), "{}", static_cast(my)); + } +}; +#endif