From 49199477905521f46e2d501b4c865b74a187f1f8 Mon Sep 17 00:00:00 2001 From: Sachin Guruswamy <43363595+saching13@users.noreply.github.com> Date: Wed, 15 Nov 2023 11:58:13 +0530 Subject: [PATCH] Ros Release 2.23 (#925) * Update FW w/ syncing stall fix * Update stereo with more robust frame sync * Update FW with optional override of spec translation for stereo algorithm calculations * Correct type * Update SPIOut.hpp to address error C4458: declaration of 'id' hides class member * Expose center alignment scale factor for debug purposes * Expose SIPP mempool configurable sizes * Update FW * Fixed usage of DeviceBootloader with incomplete DeviceInfo and added a convinience constructor * Closes: #714 * Add alpha scaling option for StereoDepth * Update FW before merge * Update FW with RGB alignment fix * Update FW with performance metrics when DEPTHAI_LEVEL=info is enabled; enable brightness filter for 0 intensity pixels by default * Improve spatial calculation X and Y accuracy; fix RGB alignment when custom output depth size is specified * [XLink] Increased max number of links from 32 to 64 * Add crash dump functionality * Change API to return just crash dump * Update FW with commit hash attached to crash dump * Update FW with fix for serialization of thread name * Add hasCrashDump API * Update FW * Update FW, crash dump contains device ID * Enable MEDAIN spatial calculation method for SpatialDetectionNetwork * Update FW * Update docs * FW: HW sync (trigger mode) enabled for OAK-D-LR, for cameras with matching FPS * Change default SIPP buffer sizes * Add 3A skipping option to reduce CPU usage * Change API to be able to configure isp 3A FPS * Update BoarConfig with limits * Update script node python bindings * Update FW: Add workaround for BNO sequence number limit of 256 (sensors sends uint8) * FW: camera sensor improvements: - AR0234 improved AE smoothness, increased max gain to 400x (first 25.6x analog), - OV9782 on RGB/CAM-A socket max FPS: 120 (previously was only for OV9282), also improves image quality in very bright light, - OV9782/9282 minimum exposure time decreased: 20us -> 10us, helps in very bright light. TODO update tuning to make use of it, currently only possible to use with manual exposure * Update stereo_depth_video.cpp * Enable interrupt mode: Update BMI driver with fixes from: https://github.com/boschsensortec/BMI270-Sensor-API/pull/16 * Update ObjectTracker with improvements from rvc3 * Add API to set trackingPerClass in ObjectTracker node * Update FW before merge * Update FW with IMU fix for BNO * Add IMU versioning; firmware versioning, firmware update status callbacks * Update FW with fix for BMI timestamp * Update FW: IMU support for OAK-D-SR * Fix 'default constrictible' error on some compilers * Update FW * Add IMU FW update RPC * Updated yolo description * Update examples * Update FW with deprecation warning for enableFirmwareUpdate * Change imu version to imu type * Update FW before merge * Added C++14 requirement to examples & tests * Tweaked crash_report example * [FW] Added missing bindings for CameraControl and ImgFrame * Update FW with fix for calibration load example * fix stability_stress_test fail to link on ubuntu - fixes luxonis/depthai-core#769 * fix isClosed/checkClosed threading, rpcClient exceptions - remove thread-unsafe checkClosed() - update isClosed() doxygen + comments - protect DataInputQueue::maxDataSize with std::atomic - remove unused dai::DeviceBase::rpcStream - fixes luxonis/depthai-core#520 * fix var hides class member, this-> in constructors - fix few compile warn 'ex' unreferenced local variable - rename setBusId() param to not hide class member - refactor XLinkConnection constructors - partial fix luxonis/depthai-core#247 * fix: stdexcept header added for std::runtime_error Signed-off-by: Onuralp SEZER * [FW] Removed UTF-8 degree sign from temperature prints. Closes: #773 * Move sipp buffer size from BoardConfig to GlobalProperties * Update style * Partially reverted bce144449056aa2a914bc70da526aebe2f359c32 - only kept the C++14 specified in examples, tests already had the version specified * [Stereo] Add option to invalidate edge pixels on disparity/depth frame * Update FW: handle disparity flipping * Update FW: support for stereo.setOutputSize when LEFT or RIGHT alignment is set * Update FW: support for stereo between RGB and LEFT/RIGHT * [FW] ImageManip CSC improvements, New boards and power cycle fix * Update FW: support for configurable ImageManip interpolation type * FW: fix for UART0 / '/dev/ttyS0' init failure in Script node * Update API to use dai::Interpolation * Update FW with latest develop fixes * Update FW with fix for USB devices stuck after reboot * Update shared * Release v2.21.0 * Fix device destructor * Update FW: fix spatial location calculator for 400p/480p resolution * Release v2.21.1 * FW: Fix camera intrinsics when RGB alignment is used * Release v2.21.2 * FW: fix running 4 cameras with Ethernet, 4th cam enabled didn't stream due to device memory allocation * prevent duplicate xlink stream names - fixes luxonis/depthai-core#469 - add test case * [FW] Fix for OAK-D-SR camera enumeration * [FW] OAK-D-LR R1 preparation * [FW / BL] Updated both FW & BL for OAK-D-LR R1. ETH fixes and moved to BNO086 IMU. * [BL] Updated to 0.0.25 release * Deprecated misleading board socket aliases * [FW] Match shared * Tweaked naming a bit more * WIP: Refactoring constructors * Added 2 additional board socket enums * Removed ; * Updated FW and fixed Device constructors * Added more checks when parsing message and a test * Add get/set to all config messages * Refactored logging to use device logger and capability to modify log levels for a specific device * Added custom spdlog logger library usage and exposed profiling data globally and per device * Updated XLink with new functionality and increased PoE search time * Added means of grabbing global profiling data as well * Updated XLink with 255.255.255.255 discovery added * Applied formatting * [Stereo] Fix auto distortion correction for 400p * [Stereo] Fix temporal filter crash on startup * Add missing info log level * Logging: fixed `DEPTHAI_DEBUG=1` causing a crash at init, `__gnu_cxx::recursive_init_error` exception due to `logger::get_level()` call * CrashDump: add optional clear of crash dump, enabled by default * Color/Mono/Camera: add `setRawOutputPacked` config -- cherry-picked, FW and shared updated in upcoming commit * ImgFrame: handle RAW10/12/14 (unpacked) like RAW16 * ToF node with ToFConfig -- cherry-picked and squashed * `make clangformat` * FW: UVC: H.264 with `ImgFrame::Type::BITSTREAM`, few more config checks * Device: fix some constructors to forward pipeline DeviceConfig * Modified XLink to a temporary branch * Updated XLink with fixed winusb mxid retrieval * FW: Stereo: handle queue blocking settings * [FW] Updated for some devices and ToF * Added filter by device name * [FW] WIP for S2 PoE boards * [FW] WIP for new SoMs * Fixed build * [FW] Fixed camera orientation * Add example for read calibration in script node * Bump version to v2.22.0 * Add to cmake and fix errors * FW: update IMX296 tuning * [FW] Fixed OAK-D-SR and OV9782 issues * Change printf to node.info in script node read calibration example * ToF: Add median filter support * Update FW to latest develop * FW: Stereo: Apply alpha scaling parameter to RGB intrinsics when RGB alignment is enabled * FW: fix CAM_D enumeration on OAK-FFC-4P R7 * Camera: move alpha parameter as optional to be consistent with stereo * Update FW * BMI: Fix accumulating latency due to slow xlink read * Fix constructors overriding maxUsbSpeed * hasAutofocus fix based on device name/lensPosition * WIP: Device name improvements * Added improvements to device naming * Fixed device related logging * Moved ts, tsDevice, and sequenceNum from descendants to RawBuffer * Added getters and setters * z_map for tof * ts to tsDevice fix * Updated ColorCamera's setSensorCrop comment for documentation * Removed redundant getters and setters * FW: add support for OAK-D-SR-PoE R1M1E1 * Fixed mistake in ImgFrame * Ran ClangFormat * Added DEPTHAI_ENABLE_LIBUSB option, to enable/disable USB protocol in build time * Applied style * Updated XLink library with some fixes * FW: fix default fsync on OAK-D-SR-PoE. GPIO46 input by default * hasautofocusIC * FW: fix 4 cams crash on PoE due to memory allocation * Update FW / shared * FW: fix OAK-D-SR camera enum. IMX296 updates: - support for RPi GS Cam paired with Luxonis SL6996 RPi camera adapter - support for external trigger on XTR/XTRIG pin: active low, pulse width determines exposure time. Limitation: needs an initial trigger shortly after start to avoid a crash, or `DEPTHAI_WATCHDOG=0` can be a workaround * Attempt to fix serialization error on windows compiler * Update FW * Implemented timesync optimization * Fixed new timesync bugs * Moved treceive back to XLink * Changes according to PR issue * Clangformat * Bump FW * WIP: Device name improvements * Added improvements to device naming * FIXME: does not work on rpi * Updated FW with changes * Bump shared * Fixed compiler error * Changed struct timespec to custom struct to fix RPI size issues * Bump shared * FW, ColorCamera: add new almost-full-FOV resolutions for IMX378/477, scaled: 1352x1012, 4lane-only, 1/3 scaling 2024x1520, 1/2 binning * Fixed incorrect warp in issue #882 * [FW] OAK-D SR PoE and ToF improvements * [FW] Improved OV9782 fps handling * Updated FW & XLink with backward compatible timestamping * FW: fixes for AR0234 fsync, AR0234 AE max exposure: 16->33 ms, more robust camera handling (especially in sync modes) * fixed the order of translation multiplication * clang update * [FW] deviceName fixes and updated for EepromData changes * Increased num XLink connections to 64 * Bumped num XLink connections to 64 * Update README.md * Update changelog and package xml * removed merge dubpicate --------- Signed-off-by: Onuralp SEZER Co-authored-by: SzabolcsGergely Co-authored-by: anonymous-1000 <124404305+anonymous-1000@users.noreply.github.com> Co-authored-by: TheMarpe Co-authored-by: TheMarpe Co-authored-by: alex-luxonis Co-authored-by: Erol444 Co-authored-by: szabi-luxonis <60790666+szabi-luxonis@users.noreply.github.com> Co-authored-by: Dale Phurrough Co-authored-by: Onuralp SEZER Co-authored-by: Florin Buica Co-authored-by: alex-luxonis <60824841+alex-luxonis@users.noreply.github.com> Co-authored-by: Andrej Susnik Co-authored-by: Aniel Alexa Co-authored-by: AnielAlexa <139551403+AnielAlexa@users.noreply.github.com> Co-authored-by: asahtik --- CHANGELOG.rst | 23 ++++ CMakeLists.txt | 16 ++- README.md | 2 + cmake/Depthai/DepthaiDeviceSideConfig.cmake | 2 +- cmake/Hunter/config.cmake | 6 +- cmake/config.hpp.in | 23 ++++ examples/CMakeLists.txt | 4 +- examples/ColorCamera/rgb_preview.cpp | 2 +- examples/Script/script_read_calibration.cpp | 43 ++++++ examples/Warp/warp_mesh.cpp | 4 +- include/depthai/common/CameraFeatures.hpp | 1 + include/depthai/device/CalibrationHandler.hpp | 31 +++++ include/depthai/device/DeviceBase.hpp | 15 ++- .../depthai/pipeline/datatype/AprilTags.hpp | 16 --- include/depthai/pipeline/datatype/Buffer.hpp | 32 +++++ .../pipeline/datatype/ImageManipConfig.hpp | 9 ++ .../pipeline/datatype/ImgDetections.hpp | 16 --- .../depthai/pipeline/datatype/ImgFrame.hpp | 19 +-- include/depthai/pipeline/datatype/NNData.hpp | 16 --- .../datatype/SpatialImgDetections.hpp | 16 --- .../SpatialLocationCalculatorData.hpp | 16 --- .../depthai/pipeline/datatype/ToFConfig.hpp | 4 + .../pipeline/datatype/TrackedFeatures.hpp | 16 --- .../depthai/pipeline/datatype/Tracklets.hpp | 16 --- include/depthai/pipeline/node/Camera.hpp | 2 +- include/depthai/pipeline/node/ColorCamera.hpp | 4 +- include/depthai/pipeline/node/Warp.hpp | 4 +- include/depthai/xlink/XLinkStream.hpp | 5 +- package.xml | 2 +- shared/depthai-shared | 2 +- src/device/CalibrationHandler.cpp | 83 ++++++++---- src/device/Device.cpp | 2 +- src/device/DeviceBase.cpp | 124 ++++++++---------- src/openvino/BlobReader.cpp | 2 +- src/pipeline/datatype/AprilTags.cpp | 28 +--- src/pipeline/datatype/Buffer.cpp | 35 +++++ src/pipeline/datatype/ImageManipConfig.cpp | 10 ++ src/pipeline/datatype/ImgDetections.cpp | 28 +--- src/pipeline/datatype/ImgFrame.cpp | 26 +--- src/pipeline/datatype/NNData.cpp | 28 +--- .../datatype/SpatialImgDetections.cpp | 28 +--- .../SpatialLocationCalculatorData.cpp | 28 +--- src/pipeline/datatype/StreamMessageParser.cpp | 15 +-- src/pipeline/datatype/ToFConfig.cpp | 5 + src/pipeline/datatype/TrackedFeatures.cpp | 28 +--- src/pipeline/datatype/Tracklets.cpp | 28 +--- src/pipeline/node/Camera.cpp | 2 +- src/pipeline/node/ColorCamera.cpp | 22 ++++ src/pipeline/node/Warp.cpp | 4 +- src/utility/EepromDataParser.cpp | 85 ++++++++++++ src/utility/EepromDataParser.hpp | 29 ++++ src/utility/Initialization.cpp | 14 +- src/utility/Path.cpp | 4 +- src/xlink/XLinkConnection.cpp | 2 +- src/xlink/XLinkStream.cpp | 20 ++- tests/CMakeLists.txt | 6 +- tests/src/device_usbspeed_test.cpp | 33 +++++ tests/src/naming_test.cpp | 113 ++++++++++++++++ 58 files changed, 735 insertions(+), 464 deletions(-) create mode 100644 examples/Script/script_read_calibration.cpp create mode 100644 src/utility/EepromDataParser.cpp create mode 100644 src/utility/EepromDataParser.hpp create mode 100644 tests/src/naming_test.cpp diff --git a/CHANGELOG.rst b/CHANGELOG.rst index f76e57fb7..6e8bc1001 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,29 @@ Changelog for package depthai ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.23.0 (2023-11-14) +----------- +* ImageManip - configurable interpolation type +* Script - added missing bindings for reading device releated data (on device calibration, etc...) +* Added Device::getDeviceName and Device::getProductName that target a user name and a "SKU" name +* Timesync - improved synchronization with tweaks to XLink +* Calibration - added housingExtrinsics +* Fix CAM_D enumeration on OAK-FFC-4P R7 +* BMI270 IMU - fix latency when slow reading +* Device related logging +* OAK-D-SR-POE - new revision bugfixes +* Fix 4 cameras crash on PoE due to memory allocation +* Fixed incorrect warp in issue #882 +* XLink - updated number of devices to 64 +* ToF - median filter and Z map support (still not the final decoding pipeline) +* hasAutofocus value fixed and introduced hasAutofocusIC +* Added timestamps and sequence numbers to all Message types +* Added DEPTHAI_ENABLE_LIBUSB for potentially disabling USB protocol (to not require libusb library) +* OV9782 and AR0234 improvements: +* OV9782 FPS improvements +* AR0234 max exposure time bump to 33ms and improved FSync INPUT mode +* Contributors: Alex Bougdan, Szabolcs Gergely, Martin Peterlin + 2.22.0 (2023-06-15) ----------- * UVC Node - Capability to create a pipeline that sends data over UVC (or flash it) diff --git a/CMakeLists.txt b/CMakeLists.txt index de13b019a..cddb3c699 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -8,6 +8,9 @@ endif() set(HUNTER_SKIP_PACKAGE_nlohmann_json OFF) set(BUILD_SHARED_LIBS ON) +# Early options +option(DEPTHAI_ENABLE_LIBUSB "Enable usage of libusb and interaction with USB devices" ON) + # Set type to canonicalize relative paths for user-provided toolchain set(CMAKE_TOOLCHAIN_FILE "" CACHE FILEPATH "CMake toolchain path") @@ -45,7 +48,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.22.0" LANGUAGES CXX C) +project(depthai VERSION "2.23.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) @@ -254,6 +257,7 @@ add_library(${TARGET_CORE_NAME} src/utility/Environment.cpp src/utility/XLinkGlobalProfilingLogger.cpp src/utility/Logging.cpp + src/utility/EepromDataParser.cpp src/xlink/XLinkConnection.cpp src/xlink/XLinkStream.cpp src/openvino/OpenVINO.cpp @@ -449,13 +453,16 @@ target_link_libraries(${TARGET_CORE_NAME} set(DEPTHAI_DEVICE_VERSION "${DEPTHAI_DEVICE_SIDE_COMMIT}") target_compile_definitions(${TARGET_CORE_NAME} PRIVATE - # XLink required define - __PC__ # Add depthai-device version DEPTHAI_DEVICE_VERSION="${DEPTHAI_DEVICE_VERSION}" # Add depthai-bootloader version DEPTHAI_BOOTLOADER_VERSION="${DEPTHAI_BOOTLOADER_VERSION}" ) +# Add compile flag if libusb is available +if(DEPTHAI_ENABLE_LIBUSB) + target_compile_definitions(${TARGET_CORE_NAME} PRIVATE DEPTHAI_ENABLE_LIBUSB) + set(DEPTHAI_HAVE_LIBUSB_SUPPORT ON) +endif() # Add Backward dependency if enabled (On by default) if(DEPTHAI_ENABLE_BACKWARD) @@ -484,8 +491,9 @@ macro(add_runtime_dependencies depending_target dependency) set(required_dll_files ${dlls} ${depthai_dll_libraries}) # Copy the required dlls add_custom_command(TARGET ${depending_target} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${required_dll_files} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${required_dll_files};$>" COMMAND_EXPAND_LISTS + VERBATIM ) message(STATUS "Required dlls for core are: ${required_dll_files}") endif() diff --git a/README.md b/README.md index ecd8a78ca..e499c363b 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,7 @@ # DepthAI C++ Library +[![Forum](https://img.shields.io/badge/Forum-discuss-orange)](https://discuss.luxonis.com/) +[![Docs](https://img.shields.io/badge/Docs-DepthAI_API-yellow)](https://docs.luxonis.com/projects/api) [![License: MIT](https://img.shields.io/badge/License-MIT-green.svg)](https://opensource.org/licenses/MIT) Core C++ library diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 86f39611d..8ad8d1296 100644 --- a/cmake/Depthai/DepthaiDeviceSideConfig.cmake +++ b/cmake/Depthai/DepthaiDeviceSideConfig.cmake @@ -2,7 +2,7 @@ set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot") # "full commit hash of device side binary" -set(DEPTHAI_DEVICE_SIDE_COMMIT "f033fd9c7eb0b3578d12f90302e87759c78cfb36") +set(DEPTHAI_DEVICE_SIDE_COMMIT "39a9d271a9ed0172f6481877723fca96d41b54c6") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 5142bc426..8b1ec7984 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -8,8 +8,10 @@ hunter_config( hunter_config( XLink VERSION "luxonis-2021.4.2-develop" - URL "https://github.com/luxonis/XLink/archive/457b23fb33e1146610e1a4e52defa7565046977a.tar.gz" - SHA1 "006a2bd391498aea7895e988b787a420e7f51fa9" + URL "https://github.com/luxonis/XLink/archive/c940feaf9321f06a7d9660f28e686a9718135f38.tar.gz" + SHA1 "52935b6ceb470ee632de3348b9d2aaa2c6c24ac0" + CMAKE_ARGS + XLINK_ENABLE_LIBUSB=${DEPTHAI_ENABLE_LIBUSB} ) hunter_config( diff --git a/cmake/config.hpp.in b/cmake/config.hpp.in index 6e1efb741..97cc44bfc 100644 --- a/cmake/config.hpp.in +++ b/cmake/config.hpp.in @@ -6,9 +6,32 @@ // This build supports OpenCV integration? #cmakedefine DEPTHAI_HAVE_OPENCV_SUPPORT +// This build supports libusb? +#cmakedefine DEPTHAI_HAVE_LIBUSB_SUPPORT + // Build specific settings overwrite #ifdef DEPTHAI_TARGET_CORE #ifndef DEPTHAI_TARGET_OPENCV #undef DEPTHAI_HAVE_OPENCV_SUPPORT #endif #endif + +namespace dai +{ +namespace build +{ + +#ifdef DEPTHAI_HAVE_OPENCV_SUPPORT + constexpr static bool HAVE_OPENCV_SUPPORT = true; +#else + constexpr static bool HAVE_OPENCV_SUPPORT = false; +#endif + +#ifdef DEPTHAI_HAVE_LIBUSB_SUPPORT + constexpr static bool HAVE_LIBUSB_SUPPORT = true; +#else + constexpr static bool HAVE_LIBUSB_SUPPORT = false; +#endif + +} // namespace build +} // namespace dai diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 41272b289..1be23d128 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -83,8 +83,9 @@ function(dai_add_example example_name example_src enable_test) set(depthai_dll_libraries "$") endif() add_custom_command(TARGET ${example_name} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${depthai_dll_libraries} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${depthai_dll_libraries};$>" COMMAND_EXPAND_LISTS + VERBATIM ) endif() endfunction() @@ -320,6 +321,7 @@ dai_add_example(script_json_communication Script/script_json_communication.cpp O dai_add_example(script_change_pipeline_flow Script/script_change_pipeline_flow.cpp OFF) target_compile_definitions(script_change_pipeline_flow PRIVATE BLOB_PATH="${mobilenet_5shaves_blob}") dai_add_example(script_get_device_info Script/script_get_device_info.cpp ON) +dai_add_example(script_read_calibration Script/script_read_calibration.cpp ON) # SpatialDetection dai_add_example(spatial_location_calculator SpatialDetection/spatial_location_calculator.cpp ON) diff --git a/examples/ColorCamera/rgb_preview.cpp b/examples/ColorCamera/rgb_preview.cpp index 1151195d4..a5d2a30cc 100644 --- a/examples/ColorCamera/rgb_preview.cpp +++ b/examples/ColorCamera/rgb_preview.cpp @@ -38,7 +38,7 @@ int main() { } // Device name - cout << "Device name: " << device.getDeviceName() << endl; + cout << "Device name: " << device.getDeviceName() << " Product name: " << device.getProductName() << endl; // Output queue will be used to get the rgb frames from the output defined above auto qRgb = device.getOutputQueue("rgb", 4, false); diff --git a/examples/Script/script_read_calibration.cpp b/examples/Script/script_read_calibration.cpp new file mode 100644 index 000000000..f3aa277ab --- /dev/null +++ b/examples/Script/script_read_calibration.cpp @@ -0,0 +1,43 @@ +#include + +// Includes common necessary includes for development using depthai library +#include "depthai/depthai.hpp" + +int main() { + using namespace std; + + // Start defining a pipeline + dai::Pipeline pipeline; + + // Script node + auto script = pipeline.create(); + script->setProcessor(dai::ProcessorType::LEON_CSS); + script->setScript(R"( + import time + + cal = Device.readCalibration2() + left_camera_id = cal.getStereoLeftCameraId() + right_camera_id = cal.getStereoRightCameraId() + + extrinsics = cal.getCameraExtrinsics(left_camera_id, right_camera_id) + intrinsics_left = cal.getCameraIntrinsics(left_camera_id) + + node.info(extrinsics.__str__()) + node.info(intrinsics_left.__str__()) + + time.sleep(1) + node.io['end'].send(Buffer(32)) + )"); + + auto xout = pipeline.create(); + xout->setStreamName("end"); + + script->outputs["end"].link(xout->input); + + // Connect to device with pipeline + dai::Device device(pipeline); + + device.getOutputQueue("end")->get(); + + return 0; +} diff --git a/examples/Warp/warp_mesh.cpp b/examples/Warp/warp_mesh.cpp index 50228fac1..66ebcbc62 100644 --- a/examples/Warp/warp_mesh.cpp +++ b/examples/Warp/warp_mesh.cpp @@ -27,7 +27,7 @@ int main() { constexpr std::tuple WARP1_OUTPUT_FRAME_SIZE = {992, 500}; warp1->setOutputSize(WARP1_OUTPUT_FRAME_SIZE); warp1->setMaxOutputFrameSize(std::get<0>(WARP1_OUTPUT_FRAME_SIZE) * std::get<1>(WARP1_OUTPUT_FRAME_SIZE) * 3); - warp1->setInterpolation(dai::node::Warp::Properties::Interpolation::BYPASS); + warp1->setInterpolation(dai::Interpolation::NEAREST_NEIGHBOR); warp1->setHwIds({1}); camRgb->preview.link(warp1->inputImage); @@ -47,7 +47,7 @@ int main() { // clang-format on warp2->setWarpMesh(mesh2, 3, 3); warp2->setMaxOutputFrameSize(maxFrameSize); - warp2->setInterpolation(dai::node::Warp::Properties::Interpolation::BICUBIC); + warp2->setInterpolation(dai::Interpolation::BICUBIC); warp2->setHwIds({2}); camRgb->preview.link(warp2->inputImage); diff --git a/include/depthai/common/CameraFeatures.hpp b/include/depthai/common/CameraFeatures.hpp index 3c552b4ff..a38e08d37 100644 --- a/include/depthai/common/CameraFeatures.hpp +++ b/include/depthai/common/CameraFeatures.hpp @@ -24,6 +24,7 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraFeatures& ca } out << "], "; out << "hasAutofocus: " << camera.hasAutofocus << ", "; + out << "hasAutofocusIC: " << camera.hasAutofocusIC << ", "; out << "name: " << camera.name << "}"; return out; diff --git a/include/depthai/device/CalibrationHandler.hpp b/include/depthai/device/CalibrationHandler.hpp index 04ba756dd..d5feb1146 100644 --- a/include/depthai/device/CalibrationHandler.hpp +++ b/include/depthai/device/CalibrationHandler.hpp @@ -353,6 +353,37 @@ class CalibrationHandler { uint32_t boardOptions, std::string boardCustom = ""); + /** + * Set the Board Info object. Creates version 7 EEPROM data + * + * @param deviceName Sets device name. + * @param productName Sets product name (alias). + * @param boardName Sets board name. + * @param boardRev Sets board revision id. + * @param boardConf Sets board configuration id. + * @param hardwareConf Sets hardware configuration id. + * @param batchName Sets batch name. Not supported anymore + * @param batchTime Sets batch time (unix timestamp). + * @param boardCustom Sets a custom board (Default empty string). + */ + void setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom = ""); + + /** + * Set the deviceName which responses to getDeviceName of Device + * + * @param deviceName Sets device name. + */ + void setDeviceName(std::string deviceName); + /** * Set the productName which acts as alisas for users to identify the device * diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 561c095bb..327f726fe 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -292,8 +292,8 @@ class DeviceBase { /** * Connects to device 'devInfo' with custom config. - * @param devInfo DeviceInfo which specifies which device to connect to * @param config Device custom configuration to boot with + * @param devInfo DeviceInfo which specifies which device to connect to */ DeviceBase(Config config, const DeviceInfo& devInfo); @@ -364,8 +364,8 @@ class DeviceBase { /** * Connects to device specified by devInfo. - * @param version OpenVINO version which the device will be booted with - * @param config Config with which specifies which device to connect to + * @param config Config with which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to * @param maxUsbSpeed Maximum allowed USB speed */ DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); @@ -456,6 +456,12 @@ class DeviceBase { */ std::string getDeviceName(); + /** + * Get product name if available + * @returns product name or empty string if not available + */ + std::string getProductName(); + /** * Get MxId of device * @@ -867,7 +873,6 @@ class DeviceBase { void init(OpenVINO::Version version); void init(OpenVINO::Version version, const dai::Path& pathToCmd); void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed); - void init(OpenVINO::Version version, bool usb2Mode, const dai::Path& pathToMvcmd); void init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); void init(const Pipeline& pipeline); void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed); @@ -876,9 +881,7 @@ class DeviceBase { void init(const Pipeline& pipeline, const DeviceInfo& devInfo, bool usb2Mode); void init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); void init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd); - void init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& pathToMvcmd); void init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); - void init(Config config, bool usb2Mode, const dai::Path& pathToMvcmd); void init(Config config, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd); void init(Config config, UsbSpeed maxUsbSpeed); void init(Config config, const dai::Path& pathToCmd); diff --git a/include/depthai/pipeline/datatype/AprilTags.hpp b/include/depthai/pipeline/datatype/AprilTags.hpp index f644302ca..f11d31f40 100644 --- a/include/depthai/pipeline/datatype/AprilTags.hpp +++ b/include/depthai/pipeline/datatype/AprilTags.hpp @@ -25,22 +25,6 @@ class AprilTags : public Buffer { std::vector& aprilTags; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/Buffer.hpp b/include/depthai/pipeline/datatype/Buffer.hpp index 921041827..57198590b 100644 --- a/include/depthai/pipeline/datatype/Buffer.hpp +++ b/include/depthai/pipeline/datatype/Buffer.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -34,6 +35,37 @@ class Buffer : public ADatatype { * @param data Moves data to internal buffer */ void setData(std::vector&& data); + + /** + * Retrieves timestamp related to dai::Clock::now() + */ + std::chrono::time_point getTimestamp() const; + + /** + * Retrieves timestamp directly captured from device's monotonic clock, + * not synchronized to host time. Used mostly for debugging + */ + std::chrono::time_point getTimestampDevice() const; + + /** + * Retrieves sequence number + */ + int64_t getSequenceNum() const; + + /** + * Sets timestamp related to dai::Clock::now() + */ + Buffer& setTimestamp(std::chrono::time_point timestamp); + + /** + * Sets timestamp related to dai::Clock::now() + */ + Buffer& setTimestampDevice(std::chrono::time_point timestamp); + + /** + * Retrieves sequence number + */ + Buffer& setSequenceNum(int64_t sequenceNum); }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ImageManipConfig.hpp b/include/depthai/pipeline/datatype/ImageManipConfig.hpp index 34953579d..f74742042 100644 --- a/include/depthai/pipeline/datatype/ImageManipConfig.hpp +++ b/include/depthai/pipeline/datatype/ImageManipConfig.hpp @@ -187,6 +187,12 @@ class ImageManipConfig : public Buffer { */ ImageManipConfig& setKeepAspectRatio(bool keep); + /** + * Specify which interpolation method to use + * @param interpolation type of interpolation + */ + ImageManipConfig& setInterpolation(dai::Interpolation interpolation); + // Functions to retrieve properties /** * @returns Top left X coordinate of crop region @@ -254,6 +260,9 @@ class ImageManipConfig : public Buffer { * @returns config for ImageManip */ dai::RawImageManipConfig get() const; + + /// Retrieve which interpolation method to use + dai::Interpolation getInterpolation() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ImgDetections.hpp b/include/depthai/pipeline/datatype/ImgDetections.hpp index 9a26304a5..53ba49fe3 100644 --- a/include/depthai/pipeline/datatype/ImgDetections.hpp +++ b/include/depthai/pipeline/datatype/ImgDetections.hpp @@ -38,22 +38,6 @@ class ImgDetections : public Buffer { * Retrieves image sequence number */ ImgDetections& setSequenceNum(int64_t sequenceNum); - - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ImgFrame.hpp b/include/depthai/pipeline/datatype/ImgFrame.hpp index 1545bc4b7..f41ef5c4b 100644 --- a/include/depthai/pipeline/datatype/ImgFrame.hpp +++ b/include/depthai/pipeline/datatype/ImgFrame.hpp @@ -31,6 +31,8 @@ class ImgFrame : public Buffer { using Type = RawImgFrame::Type; using Specs = RawImgFrame::Specs; using CameraSettings = RawImgFrame::CameraSettings; + using Buffer::getTimestamp; + using Buffer::getTimestampDevice; /** * Construct ImgFrame message. @@ -40,18 +42,6 @@ class ImgFrame : public Buffer { explicit ImgFrame(std::shared_ptr ptr); virtual ~ImgFrame() = default; - // getters - /** - * Retrieves image timestamp (end of exposure) related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp (end of exposure) directly captured from device's monotonic clock, - * not synchronized to host time. Used when monotonicity is required. - */ - std::chrono::time_point getTimestampDevice() const; - // getters /** * Retrieves image timestamp (at the specified offset of exposure) related to dai::Clock::now() @@ -74,11 +64,6 @@ class ImgFrame : public Buffer { */ unsigned int getCategory() const; - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Retrieves image width in pixels */ diff --git a/include/depthai/pipeline/datatype/NNData.hpp b/include/depthai/pipeline/datatype/NNData.hpp index 980b32102..814f4c948 100644 --- a/include/depthai/pipeline/datatype/NNData.hpp +++ b/include/depthai/pipeline/datatype/NNData.hpp @@ -140,22 +140,6 @@ class NNData : public Buffer { */ std::vector getFirstLayerInt32() const; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/SpatialImgDetections.hpp b/include/depthai/pipeline/datatype/SpatialImgDetections.hpp index 0e0a76f5d..30876a462 100644 --- a/include/depthai/pipeline/datatype/SpatialImgDetections.hpp +++ b/include/depthai/pipeline/datatype/SpatialImgDetections.hpp @@ -43,22 +43,6 @@ class SpatialImgDetections : public Buffer { * Retrieves image sequence number */ SpatialImgDetections& setSequenceNum(int64_t sequenceNum); - - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp b/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp index 9f2cda338..c6a5586a9 100644 --- a/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp +++ b/include/depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp @@ -31,22 +31,6 @@ class SpatialLocationCalculatorData : public Buffer { std::vector& spatialLocations; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/ToFConfig.hpp b/include/depthai/pipeline/datatype/ToFConfig.hpp index 39a8adf08..0d877ee99 100644 --- a/include/depthai/pipeline/datatype/ToFConfig.hpp +++ b/include/depthai/pipeline/datatype/ToFConfig.hpp @@ -30,6 +30,10 @@ class ToFConfig : public Buffer { ToFConfig& setFreqModUsed(dai::ToFConfig::DepthParams::TypeFMod fmod); ToFConfig& setAvgPhaseShuffle(bool enable); ToFConfig& setMinAmplitude(float minamp); + /** + * @param median Set kernel size for median filtering, or disable + */ + ToFConfig& setMedianFilter(MedianFilter median); /** * Set explicit configuration. diff --git a/include/depthai/pipeline/datatype/TrackedFeatures.hpp b/include/depthai/pipeline/datatype/TrackedFeatures.hpp index 158c83b03..45817658e 100644 --- a/include/depthai/pipeline/datatype/TrackedFeatures.hpp +++ b/include/depthai/pipeline/datatype/TrackedFeatures.hpp @@ -25,22 +25,6 @@ class TrackedFeatures : public Buffer { std::vector& trackedFeatures; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/datatype/Tracklets.hpp b/include/depthai/pipeline/datatype/Tracklets.hpp index f5ba6543d..278818d4b 100644 --- a/include/depthai/pipeline/datatype/Tracklets.hpp +++ b/include/depthai/pipeline/datatype/Tracklets.hpp @@ -30,22 +30,6 @@ class Tracklets : public Buffer { */ std::vector& tracklets; - /** - * Retrieves image timestamp related to dai::Clock::now() - */ - std::chrono::time_point getTimestamp() const; - - /** - * Retrieves image timestamp directly captured from device's monotonic clock, - * not synchronized to host time. Used mostly for debugging - */ - std::chrono::time_point getTimestampDevice() const; - - /** - * Retrieves image sequence number - */ - int64_t getSequenceNum() const; - /** * Sets image timestamp related to dai::Clock::now() */ diff --git a/include/depthai/pipeline/node/Camera.hpp b/include/depthai/pipeline/node/Camera.hpp index bb44afa68..0e7f2c778 100644 --- a/include/depthai/pipeline/node/Camera.hpp +++ b/include/depthai/pipeline/node/Camera.hpp @@ -333,7 +333,7 @@ class Camera : public NodeCRTP { /// Set calibration alpha parameter that determines FOV of undistorted frames void setCalibrationAlpha(float alpha); /// Get calibration alpha parameter that determines FOV of undistorted frames - float getCalibrationAlpha() const; + tl::optional getCalibrationAlpha() const; /** * Configures whether the camera `raw` frames are saved as MIPI-packed to memory. diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index dc2e1b2e2..0f2890e71 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -286,7 +286,9 @@ class ColorCamera : public NodeCRTP { void sensorCenterCrop(); /** - * Specifies sensor crop rectangle + * Specifies the cropping that happens when converting ISP to video output. By default, video will be center cropped + * from the ISP output. Note that this doesn't actually do on-sensor cropping (and MIPI-stream only that region), but + * it does postprocessing on the ISP (on RVC). * @param x Top left X coordinate * @param y Top left Y coordinate */ diff --git a/include/depthai/pipeline/node/Warp.hpp b/include/depthai/pipeline/node/Warp.hpp index b86f608e3..836a69516 100644 --- a/include/depthai/pipeline/node/Warp.hpp +++ b/include/depthai/pipeline/node/Warp.hpp @@ -90,9 +90,9 @@ class Warp : public NodeCRTP { * Specify which interpolation method to use * @param interpolation type of interpolation */ - void setInterpolation(Properties::Interpolation interpolation); + void setInterpolation(dai::Interpolation interpolation); /// Retrieve which interpolation method to use - Properties::Interpolation getInterpolation() const; + dai::Interpolation getInterpolation() const; }; } // namespace node diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index 47bc9ace2..9b0865425 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -17,6 +17,7 @@ // libraries #include +#include // project #include "depthai/xlink/XLinkConnection.hpp" @@ -25,7 +26,7 @@ namespace dai { class StreamPacketDesc : public streamPacketDesc_t { public: - StreamPacketDesc() noexcept : streamPacketDesc_t{nullptr, 0} {}; + StreamPacketDesc() noexcept : streamPacketDesc_t{nullptr, 0, {}, {}} {}; StreamPacketDesc(const StreamPacketDesc&) = delete; StreamPacketDesc(StreamPacketDesc&& other) noexcept; StreamPacketDesc& operator=(const StreamPacketDesc&) = delete; @@ -55,7 +56,9 @@ class XLinkStream { void write(const std::uint8_t* data, std::size_t size); void write(const std::vector& data); std::vector read(); + std::vector read(XLinkTimespec& timestampReceived); void read(std::vector& data); + void read(std::vector& data, XLinkTimespec& timestampReceived); // split write helper void writeSplit(const void* data, std::size_t size, std::size_t split); void writeSplit(const std::vector& data, std::size_t split); diff --git a/package.xml b/package.xml index dae23a4f1..69619ad0b 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ depthai - 2.22.0 + 2.23.0 DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform Sachin Guruswamy diff --git a/shared/depthai-shared b/shared/depthai-shared index f03e9d9b0..8bacf258a 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit f03e9d9b08df2c0a50b8a928901ce95b14f9c174 +Subproject commit 8bacf258a2ccf507634da153a7166aec77af1ea7 diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 15a4b6a29..cf74c1361 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -419,24 +419,25 @@ std::vector> CalibrationHandler::getImuToCameraExtrinsics(Cam throw std::runtime_error("There is no Camera data available corresponding to the requested source cameraId"); } - std::vector> transformationMatrix = eepromData.imuExtrinsics.rotationMatrix; + std::vector> currTransformationMatrixImu = eepromData.imuExtrinsics.rotationMatrix; if(useSpecTranslation) { - transformationMatrix[0].push_back(eepromData.imuExtrinsics.specTranslation.x); - transformationMatrix[1].push_back(eepromData.imuExtrinsics.specTranslation.y); - transformationMatrix[2].push_back(eepromData.imuExtrinsics.specTranslation.z); + currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.specTranslation.x); + currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.specTranslation.y); + currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.specTranslation.z); } else { - transformationMatrix[0].push_back(eepromData.imuExtrinsics.translation.x); - transformationMatrix[1].push_back(eepromData.imuExtrinsics.translation.y); - transformationMatrix[2].push_back(eepromData.imuExtrinsics.translation.z); + currTransformationMatrixImu[0].push_back(eepromData.imuExtrinsics.translation.x); + currTransformationMatrixImu[1].push_back(eepromData.imuExtrinsics.translation.y); + currTransformationMatrixImu[2].push_back(eepromData.imuExtrinsics.translation.z); } std::vector homogeneous_vector = {0, 0, 0, 1}; - transformationMatrix.push_back(homogeneous_vector); + currTransformationMatrixImu.push_back(homogeneous_vector); if(eepromData.imuExtrinsics.toCameraSocket == cameraId) { - return transformationMatrix; + return currTransformationMatrixImu; } else { - std::vector> localTransformationMatrix = getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); - return matMul(transformationMatrix, localTransformationMatrix); + std::vector> destTransformationMatrixCurr = + getCameraExtrinsics(eepromData.imuExtrinsics.toCameraSocket, cameraId, useSpecTranslation); + return matMul(destTransformationMatrixCurr, currTransformationMatrixImu); } } @@ -506,25 +507,25 @@ std::vector> CalibrationHandler::computeExtrinsicMatrix(Camer transformationMatrix.push_back(homogeneous_vector); return transformationMatrix; } else { - std::vector> futureTransformationMatrix = + std::vector> destTransformationMatrixCurr = computeExtrinsicMatrix(eepromData.cameraData.at(srcCamera).extrinsics.toCameraSocket, dstCamera, useSpecTranslation); - std::vector> currTransformationMatrix = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix; + std::vector> currTransformationMatrixSrc = eepromData.cameraData.at(srcCamera).extrinsics.rotationMatrix; if(useSpecTranslation) { const dai::Point3f& mTrans = eepromData.cameraData.at(srcCamera).extrinsics.specTranslation; if(mTrans.x == 0 && mTrans.y == 0 && mTrans.z == 0) { throw std::runtime_error("Cannot use useSpecTranslation argument since specTranslation has {0, 0, 0}"); } - currTransformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x); - currTransformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y); - currTransformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z); + currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.x); + currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.y); + currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.specTranslation.z); } else { - currTransformationMatrix[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x); - currTransformationMatrix[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y); - currTransformationMatrix[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z); + currTransformationMatrixSrc[0].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.x); + currTransformationMatrixSrc[1].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.y); + currTransformationMatrixSrc[2].push_back(eepromData.cameraData.at(srcCamera).extrinsics.translation.z); } std::vector homogeneous_vector = {0, 0, 0, 1}; - currTransformationMatrix.push_back(homogeneous_vector); - return matMul(currTransformationMatrix, futureTransformationMatrix); + currTransformationMatrixSrc.push_back(homogeneous_vector); + return matMul(destTransformationMatrixCurr, currTransformationMatrixSrc); } } @@ -560,11 +561,49 @@ void CalibrationHandler::setBoardInfo(std::string productName, eepromData.boardRev = boardRev; eepromData.boardConf = boardConf; eepromData.hardwareConf = hardwareConf; - eepromData.batchName = batchName; eepromData.batchTime = batchTime; eepromData.boardCustom = boardCustom; eepromData.boardOptions = boardOptions; + if(batchName != "") { + logger::warn("batchName parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setBoardInfo(std::string deviceName, + std::string productName, + std::string boardName, + std::string boardRev, + std::string boardConf, + std::string hardwareConf, + std::string batchName, + uint64_t batchTime, + uint32_t boardOptions, + std::string boardCustom) { + eepromData.productName = productName; + eepromData.boardName = boardName; + eepromData.boardRev = boardRev; + eepromData.boardConf = boardConf; + eepromData.hardwareConf = hardwareConf; + eepromData.batchTime = batchTime; + eepromData.boardCustom = boardCustom; + eepromData.boardOptions = boardOptions; + eepromData.deviceName = deviceName; + + if(batchName != "") { + logger::warn("batchName parameter not supported anymore"); + } + + // Bump version to V7 + eepromData.version = 7; +} + +void CalibrationHandler::setDeviceName(std::string deviceName) { + eepromData.deviceName = deviceName; + // Bump version to V7 eepromData.version = 7; } diff --git a/src/device/Device.cpp b/src/device/Device.cpp index feabee10f..3cdf3948e 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -41,7 +41,7 @@ Device::Device(const Pipeline& pipeline, const dai::Path& pathToCmd) : DeviceBas tryStartPipeline(pipeline); } -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getDeviceConfig(), devInfo, false) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getDeviceConfig(), devInfo) { tryStartPipeline(pipeline); } diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 607568ac0..6994860ff 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -21,6 +21,7 @@ #include "depthai/pipeline/node/XLinkIn.hpp" #include "depthai/pipeline/node/XLinkOut.hpp" #include "pipeline/Pipeline.hpp" +#include "utility/EepromDataParser.hpp" #include "utility/Environment.hpp" #include "utility/Initialization.hpp" #include "utility/PimplImpl.hpp" @@ -28,6 +29,7 @@ // libraries #include "XLink/XLink.h" +#include "XLink/XLinkTime.h" #include "nanorpc/core/client.h" #include "nanorpc/packer/nlohmann_msgpack.h" #include "spdlog/details/os.h" @@ -333,7 +335,10 @@ DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, Usb } DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { - init(version, false, pathToCmd); + Config cfg; + cfg.version = version; + + init2(cfg, pathToCmd, {}); } DeviceBase::DeviceBase() : DeviceBase(OpenVINO::VERSION_UNIVERSAL) {} @@ -394,7 +399,7 @@ DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsb } DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } DeviceBase::DeviceBase(Config config, const dai::Path& pathToCmd) { @@ -407,12 +412,20 @@ DeviceBase::DeviceBase(Config config, UsbSpeed maxUsbSpeed) { void DeviceBase::init(OpenVINO::Version version) { tryGetDevice(); - init(version, false, ""); + + Config cfg; + cfg.version = version; + + init2(cfg, "", {}); } void DeviceBase::init(OpenVINO::Version version, const dai::Path& pathToCmd) { tryGetDevice(); - init(version, false, pathToCmd); + + Config cfg; + cfg.version = version; + + init2(cfg, pathToCmd, {}); } void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { @@ -422,7 +435,10 @@ void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { void DeviceBase::init(const Pipeline& pipeline) { tryGetDevice(); - init(pipeline, false, ""); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, "", pipeline); } void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { @@ -432,12 +448,18 @@ void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { void DeviceBase::init(const Pipeline& pipeline, const dai::Path& pathToCmd) { tryGetDevice(); - init(pipeline, false, pathToCmd); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, pathToCmd, pipeline); } void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo) { deviceInfo = devInfo; - init(pipeline, false, ""); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, "", pipeline); } void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { @@ -447,7 +469,10 @@ void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSp void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { deviceInfo = devInfo; - init(pipeline, false, pathToCmd); + + Config cfg = pipeline.getDeviceConfig(); + + init2(cfg, pathToCmd, pipeline); } void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) { @@ -457,7 +482,7 @@ void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) { void DeviceBase::init(Config config, const dai::Path& pathToCmd) { tryGetDevice(); - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { @@ -467,7 +492,7 @@ void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbS void DeviceBase::init(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { deviceInfo = devInfo; - init(config, false, pathToCmd); + init2(config, pathToCmd, {}); } DeviceBase::DeviceBase(Config config) { @@ -548,26 +573,6 @@ void DeviceBase::tryStartPipeline(const Pipeline& pipeline) { } } -void DeviceBase::init(OpenVINO::Version version, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg; - // Specify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - // Specify the OpenVINO version - cfg.version = version; - init2(cfg, pathToMvcmd, {}); -} -void DeviceBase::init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg = pipeline.getDeviceConfig(); - // Modify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - init2(cfg, pathToMvcmd, pipeline); -} -void DeviceBase::init(Config config, bool usb2Mode, const dai::Path& pathToMvcmd) { - Config cfg = config; - // Modify usb speed - cfg.board.usb.maxSpeed = usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED; - init2(cfg, pathToMvcmd, {}); -} void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) { Config cfg; // Specify usb speed @@ -599,6 +604,12 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Device - BoardConfig: {} \nlibnop:{}", jBoardConfig.dump(), spdlog::to_hex(utility::serialize(config.board))); } @@ -735,7 +746,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional lock(pimpl->rpcMutex); // Log the request data - if(logger::get_level() == spdlog::level::trace) { + if(getLogOutputLevel() == LogLevel::TRACE) { pimpl->logger.trace("RPC: {}", nlohmann::json::from_msgpack(request).dump()); } @@ -818,7 +829,6 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(d).count(); - timestamp.nsec = duration_cast(d).count() % 1000000000; + XLinkTimespec timestamp; + stream.read(timestamp); // Write timestamp back stream.write(×tamp, sizeof(timestamp)); @@ -914,8 +919,8 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(w / rate); + r = static_cast(r / rate); lastData = data; @@ -1059,31 +1064,16 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } -std::string DeviceBase::getDeviceName() { - std::string deviceName; - EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - eeprom = readCalibrationOrDefault().getEepromData(); - if((deviceName = eeprom.productName).empty()) { - deviceName = eeprom.boardName; - } - } - - // Convert to device naming from display/product naming - // std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); - std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), [](int c) { return std::toupper(c); }); - std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); - - // Handle some known legacy cases - if(deviceName == "BW1098OBC") { - deviceName = "OAK-D"; - } else if(deviceName == "DM2097") { - deviceName = "OAK-D-CM4-POE"; - } else if(deviceName == "BW1097") { - deviceName = "OAK-D-CM3"; - } +std::string DeviceBase::getProductName() { + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + return utility::parseProductName(eeprom, eepromFactory); +} - return deviceName; +std::string DeviceBase::getDeviceName() { + EepromData eepromFactory = readFactoryCalibrationOrDefault().getEepromData(); + EepromData eeprom = readCalibrationOrDefault().getEepromData(); + return utility::parseDeviceName(eeprom, eepromFactory); } void DeviceBase::setLogOutputLevel(LogLevel level) { @@ -1364,7 +1354,7 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { pipeline.serialize(schema, assets, assetStorage); // if debug or lower - if(logger::get_level() <= spdlog::level::debug) { + if(getLogOutputLevel() <= LogLevel::DEBUG) { nlohmann::json jSchema = schema; pimpl->logger.debug("Schema dump: {}", jSchema.dump()); nlohmann::json jAssets = assets; diff --git a/src/openvino/BlobReader.cpp b/src/openvino/BlobReader.cpp index de6010002..148ce8c7e 100644 --- a/src/openvino/BlobReader.cpp +++ b/src/openvino/BlobReader.cpp @@ -18,7 +18,7 @@ #include "BlobFormat.hpp" // TODO(themarpe) -//#include +// #include namespace dai { diff --git a/src/pipeline/datatype/AprilTags.cpp b/src/pipeline/datatype/AprilTags.cpp index 38fba14c9..fa81e5bb5 100644 --- a/src/pipeline/datatype/AprilTags.cpp +++ b/src/pipeline/datatype/AprilTags.cpp @@ -10,39 +10,17 @@ AprilTags::AprilTags() : Buffer(std::make_shared()), rawdata(*dyna AprilTags::AprilTags(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), aprilTags(rawdata.aprilTags) {} -// getters -std::chrono::time_point AprilTags::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point AprilTags::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t AprilTags::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters AprilTags& AprilTags::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } AprilTags& AprilTags::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } AprilTags& AprilTags::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai \ No newline at end of file diff --git a/src/pipeline/datatype/Buffer.cpp b/src/pipeline/datatype/Buffer.cpp index fca09ebce..a0251d7bf 100644 --- a/src/pipeline/datatype/Buffer.cpp +++ b/src/pipeline/datatype/Buffer.cpp @@ -22,4 +22,39 @@ void Buffer::setData(std::vector&& data) { raw->data = std::move(data); } +// getters +std::chrono::time_point Buffer::getTimestamp() const { + using namespace std::chrono; + return time_point{seconds(raw->ts.sec) + nanoseconds(raw->ts.nsec)}; +} +std::chrono::time_point Buffer::getTimestampDevice() const { + using namespace std::chrono; + return time_point{seconds(raw->tsDevice.sec) + nanoseconds(raw->tsDevice.nsec)}; +} +int64_t Buffer::getSequenceNum() const { + return raw->sequenceNum; +} + +// setters +Buffer& Buffer::setTimestamp(std::chrono::time_point tp) { + // Set timestamp from timepoint + using namespace std::chrono; + auto ts = tp.time_since_epoch(); + raw->ts.sec = duration_cast(ts).count(); + raw->ts.nsec = duration_cast(ts).count() % 1000000000; + return *this; +} +Buffer& Buffer::setTimestampDevice(std::chrono::time_point tp) { + // Set timestamp from timepoint + using namespace std::chrono; + auto ts = tp.time_since_epoch(); + raw->tsDevice.sec = duration_cast(ts).count(); + raw->tsDevice.nsec = duration_cast(ts).count() % 1000000000; + return *this; +} +Buffer& Buffer::setSequenceNum(int64_t sequenceNum) { + raw->sequenceNum = sequenceNum; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index f22c40ab0..126e6edd5 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -48,6 +48,7 @@ ImageManipConfig& ImageManipConfig::setCropRotatedRect(RotatedRect rr, bool norm ImageManipConfig& ImageManipConfig::setWarpTransformFourPoints(std::vector pt, bool normalizedCoords) { // Enable resize stage and extended flags cfg.enableResize = true; + cfg.resizeConfig.keepAspectRatio = false; cfg.resizeConfig.enableWarp4pt = true; cfg.resizeConfig.warpFourPoints = pt; cfg.resizeConfig.normalizedCoords = normalizedCoords; @@ -234,6 +235,11 @@ ImageManipConfig& ImageManipConfig::setKeepAspectRatio(bool keep) { return *this; } +ImageManipConfig& ImageManipConfig::setInterpolation(dai::Interpolation interpolation) { + cfg.interpolation = interpolation; + return *this; +} + // Functions to retrieve properties float ImageManipConfig::getCropXMin() const { return cfg.cropConfig.cropRect.xmin; @@ -288,4 +294,8 @@ ImageManipConfig& ImageManipConfig::set(dai::RawImageManipConfig config) { return *this; } +dai::Interpolation ImageManipConfig::getInterpolation() const { + return cfg.interpolation; +} + } // namespace dai diff --git a/src/pipeline/datatype/ImgDetections.cpp b/src/pipeline/datatype/ImgDetections.cpp index c0d9ad85c..b9eb5f75d 100644 --- a/src/pipeline/datatype/ImgDetections.cpp +++ b/src/pipeline/datatype/ImgDetections.cpp @@ -13,36 +13,14 @@ ImgDetections::ImgDetections(std::shared_ptr ptr) // setters ImgDetections& ImgDetections::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.ts.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } ImgDetections& ImgDetections::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.tsDevice.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } ImgDetections& ImgDetections::setSequenceNum(int64_t sequenceNum) { - dets.sequenceNum = sequenceNum; - return *this; -} - -// getters -std::chrono::time_point ImgDetections::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(dets.ts.sec) + nanoseconds(dets.ts.nsec)}; -} -std::chrono::time_point ImgDetections::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(dets.tsDevice.sec) + nanoseconds(dets.tsDevice.nsec)}; -} -int64_t ImgDetections::getSequenceNum() const { - return dets.sequenceNum; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/ImgFrame.cpp b/src/pipeline/datatype/ImgFrame.cpp index d7f98d8a9..279c72ccd 100644 --- a/src/pipeline/datatype/ImgFrame.cpp +++ b/src/pipeline/datatype/ImgFrame.cpp @@ -17,14 +17,6 @@ ImgFrame::ImgFrame(std::shared_ptr ptr) : Buffer(std::move(ptr)), i // helpers // getters -std::chrono::time_point ImgFrame::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(img.ts.sec) + nanoseconds(img.ts.nsec)}; -} -std::chrono::time_point ImgFrame::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(img.tsDevice.sec) + nanoseconds(img.tsDevice.nsec)}; -} std::chrono::time_point ImgFrame::getTimestamp(CameraExposureOffset offset) const { auto ts = getTimestamp(); auto expTime = getExposureTime(); @@ -58,9 +50,6 @@ unsigned int ImgFrame::getInstanceNum() const { unsigned int ImgFrame::getCategory() const { return img.category; } -int64_t ImgFrame::getSequenceNum() const { - return img.sequenceNum; -} unsigned int ImgFrame::getWidth() const { return img.fb.width; } @@ -86,19 +75,11 @@ int ImgFrame::getLensPosition() const { // setters ImgFrame& ImgFrame::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - img.ts.sec = duration_cast(ts).count(); - img.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } ImgFrame& ImgFrame::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - img.tsDevice.sec = duration_cast(ts).count(); - img.tsDevice.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } ImgFrame& ImgFrame::setInstanceNum(unsigned int instanceNum) { img.instanceNum = instanceNum; @@ -109,8 +90,7 @@ ImgFrame& ImgFrame::setCategory(unsigned int category) { return *this; } ImgFrame& ImgFrame::setSequenceNum(int64_t sequenceNum) { - img.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } ImgFrame& ImgFrame::setWidth(unsigned int width) { img.fb.width = width; diff --git a/src/pipeline/datatype/NNData.cpp b/src/pipeline/datatype/NNData.cpp index aa35ce9eb..ab765e63b 100644 --- a/src/pipeline/datatype/NNData.cpp +++ b/src/pipeline/datatype/NNData.cpp @@ -269,39 +269,17 @@ std::vector NNData::getFirstLayerInt32() const { return {}; } -// getters -std::chrono::time_point NNData::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawNn.ts.sec) + nanoseconds(rawNn.ts.nsec)}; -} -std::chrono::time_point NNData::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawNn.tsDevice.sec) + nanoseconds(rawNn.tsDevice.nsec)}; -} -int64_t NNData::getSequenceNum() const { - return rawNn.sequenceNum; -} - // setters NNData& NNData::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawNn.ts.sec = duration_cast(ts).count(); - rawNn.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } NNData& NNData::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawNn.tsDevice.sec = duration_cast(ts).count(); - rawNn.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } NNData& NNData::setSequenceNum(int64_t sequenceNum) { - rawNn.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/SpatialImgDetections.cpp b/src/pipeline/datatype/SpatialImgDetections.cpp index 76210ddea..89ee58e8d 100644 --- a/src/pipeline/datatype/SpatialImgDetections.cpp +++ b/src/pipeline/datatype/SpatialImgDetections.cpp @@ -14,36 +14,14 @@ SpatialImgDetections::SpatialImgDetections(std::shared_ptr tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.ts.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } SpatialImgDetections& SpatialImgDetections::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - dets.tsDevice.sec = duration_cast(ts).count(); - dets.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } SpatialImgDetections& SpatialImgDetections::setSequenceNum(int64_t sequenceNum) { - dets.sequenceNum = sequenceNum; - return *this; -} - -// getters -std::chrono::time_point SpatialImgDetections::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(dets.ts.sec) + nanoseconds(dets.ts.nsec)}; -} -std::chrono::time_point SpatialImgDetections::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(dets.tsDevice.sec) + nanoseconds(dets.tsDevice.nsec)}; -} -int64_t SpatialImgDetections::getSequenceNum() const { - return dets.sequenceNum; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/SpatialLocationCalculatorData.cpp b/src/pipeline/datatype/SpatialLocationCalculatorData.cpp index 16e99abc5..c6edf0e3d 100644 --- a/src/pipeline/datatype/SpatialLocationCalculatorData.cpp +++ b/src/pipeline/datatype/SpatialLocationCalculatorData.cpp @@ -15,41 +15,19 @@ std::vector& SpatialLocationCalculatorData::getSpatialLocation return rawdata.spatialLocations; } -// getters -std::chrono::time_point SpatialLocationCalculatorData::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point SpatialLocationCalculatorData::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t SpatialLocationCalculatorData::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters SpatialLocationCalculatorData& SpatialLocationCalculatorData::setTimestamp( std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } SpatialLocationCalculatorData& SpatialLocationCalculatorData::setTimestampDevice( std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } SpatialLocationCalculatorData& SpatialLocationCalculatorData::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/StreamMessageParser.cpp b/src/pipeline/datatype/StreamMessageParser.cpp index a000b205d..db52b55d4 100644 --- a/src/pipeline/datatype/StreamMessageParser.cpp +++ b/src/pipeline/datatype/StreamMessageParser.cpp @@ -114,13 +114,9 @@ std::shared_ptr StreamMessageParser::parseMessage(streamPacketDesc_t* // Create corresponding object switch(objectType) { - // RawBuffer is special case, no metadata is actually serialized - case DatatypeEnum::Buffer: { - // RawBuffer is special case, no metadata is actually serialized - auto pBuf = std::make_shared(); - pBuf->data = std::move(data); - return pBuf; - } break; + case DatatypeEnum::Buffer: + return parseDatatype(metadataStart, serializedObjectSize, data); + break; case DatatypeEnum::ImgFrame: return parseDatatype(metadataStart, serializedObjectSize, data); @@ -210,10 +206,7 @@ std::shared_ptr StreamMessageParser::parseMessageToADatatype(streamPa switch(objectType) { case DatatypeEnum::Buffer: { - // RawBuffer is special case, no metadata is actually serialized - auto pBuf = std::make_shared(); - pBuf->data = std::move(data); - return std::make_shared(pBuf); + return std::make_shared(parseDatatype(metadataStart, serializedObjectSize, data)); } break; case DatatypeEnum::ImgFrame: diff --git a/src/pipeline/datatype/ToFConfig.cpp b/src/pipeline/datatype/ToFConfig.cpp index 4f8a625be..da1ce41ed 100644 --- a/src/pipeline/datatype/ToFConfig.cpp +++ b/src/pipeline/datatype/ToFConfig.cpp @@ -38,4 +38,9 @@ ToFConfig& ToFConfig::setMinAmplitude(float minamp) { return *this; } +ToFConfig& ToFConfig::setMedianFilter(MedianFilter median) { + cfg.depthParams.median = median; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/TrackedFeatures.cpp b/src/pipeline/datatype/TrackedFeatures.cpp index 7e3361c9c..81ad8ddaa 100644 --- a/src/pipeline/datatype/TrackedFeatures.cpp +++ b/src/pipeline/datatype/TrackedFeatures.cpp @@ -11,39 +11,17 @@ TrackedFeatures::TrackedFeatures() TrackedFeatures::TrackedFeatures(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), trackedFeatures(rawdata.trackedFeatures) {} -// getters -std::chrono::time_point TrackedFeatures::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point TrackedFeatures::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t TrackedFeatures::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters TrackedFeatures& TrackedFeatures::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } TrackedFeatures& TrackedFeatures::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } TrackedFeatures& TrackedFeatures::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/datatype/Tracklets.cpp b/src/pipeline/datatype/Tracklets.cpp index 7efc931a6..d6c282efd 100644 --- a/src/pipeline/datatype/Tracklets.cpp +++ b/src/pipeline/datatype/Tracklets.cpp @@ -10,39 +10,17 @@ Tracklets::Tracklets() : Buffer(std::make_shared()), rawdata(*dyna Tracklets::Tracklets(std::shared_ptr ptr) : Buffer(std::move(ptr)), rawdata(*dynamic_cast(raw.get())), tracklets(rawdata.tracklets) {} -// getters -std::chrono::time_point Tracklets::getTimestamp() const { - using namespace std::chrono; - return time_point{seconds(rawdata.ts.sec) + nanoseconds(rawdata.ts.nsec)}; -} -std::chrono::time_point Tracklets::getTimestampDevice() const { - using namespace std::chrono; - return time_point{seconds(rawdata.tsDevice.sec) + nanoseconds(rawdata.tsDevice.nsec)}; -} -int64_t Tracklets::getSequenceNum() const { - return rawdata.sequenceNum; -} - // setters Tracklets& Tracklets::setTimestamp(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.ts.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestamp(tp)); } Tracklets& Tracklets::setTimestampDevice(std::chrono::time_point tp) { // Set timestamp from timepoint - using namespace std::chrono; - auto ts = tp.time_since_epoch(); - rawdata.tsDevice.sec = duration_cast(ts).count(); - rawdata.ts.nsec = duration_cast(ts).count() % 1000000000; - return *this; + return static_cast(Buffer::setTimestampDevice(tp)); } Tracklets& Tracklets::setSequenceNum(int64_t sequenceNum) { - rawdata.sequenceNum = sequenceNum; - return *this; + return static_cast(Buffer::setSequenceNum(sequenceNum)); } } // namespace dai diff --git a/src/pipeline/node/Camera.cpp b/src/pipeline/node/Camera.cpp index 6edcc1150..66516d10e 100644 --- a/src/pipeline/node/Camera.cpp +++ b/src/pipeline/node/Camera.cpp @@ -271,7 +271,7 @@ void Camera::setCalibrationAlpha(float alpha) { properties.calibAlpha = alpha; } -float Camera::getCalibrationAlpha() const { +tl::optional Camera::getCalibrationAlpha() const { return properties.calibAlpha; } diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index ff021d5ae..23d479464 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -251,6 +251,12 @@ std::tuple ColorCamera::getVideoSize() const { if(properties.resolution == ColorCameraProperties::SensorResolution::THE_1440X1080) { maxVideoWidth = 1440; } + if(properties.resolution == ColorCameraProperties::SensorResolution::THE_2024X1520) { + maxVideoWidth = 2024; + } + if(properties.resolution == ColorCameraProperties::SensorResolution::THE_1352X1012) { + maxVideoWidth = 1352; + } // Take into the account the ISP scaling int numW = properties.ispScale.horizNumerator; @@ -320,6 +326,14 @@ std::tuple ColorCamera::getStillSize() const { maxStillWidth = 1440; maxStillHeight = 1080; } + if(properties.resolution == dai::ColorCameraProperties::SensorResolution::THE_2024X1520) { + maxStillWidth = 2024; + maxStillHeight = 1520; + } + if(properties.resolution == dai::ColorCameraProperties::SensorResolution::THE_1352X1012) { + maxStillWidth = 1352; + maxStillHeight = 1012; + } // Take into the account the ISP scaling int numW = properties.ispScale.horizNumerator; @@ -399,6 +413,14 @@ std::tuple ColorCamera::getResolutionSize() const { case ColorCameraProperties::SensorResolution::THE_1440X1080: return {1440, 1080}; break; + + case ColorCameraProperties::SensorResolution::THE_2024X1520: + return {2024, 1520}; + break; + + case ColorCameraProperties::SensorResolution::THE_1352X1012: + return {1352, 1012}; + break; } return {1920, 1080}; diff --git a/src/pipeline/node/Warp.cpp b/src/pipeline/node/Warp.cpp index 43c7a4b86..d088e2947 100644 --- a/src/pipeline/node/Warp.cpp +++ b/src/pipeline/node/Warp.cpp @@ -86,11 +86,11 @@ std::vector Warp::getHwIds() const { return properties.warpHwIds; } -void Warp::setInterpolation(Warp::Properties::Interpolation interpolation) { +void Warp::setInterpolation(dai::Interpolation interpolation) { properties.interpolation = interpolation; } -Warp::Properties::Interpolation Warp::getInterpolation() const { +dai::Interpolation Warp::getInterpolation() const { return properties.interpolation; } diff --git a/src/utility/EepromDataParser.cpp b/src/utility/EepromDataParser.cpp new file mode 100644 index 000000000..b863bf8da --- /dev/null +++ b/src/utility/EepromDataParser.cpp @@ -0,0 +1,85 @@ +#include "utility/EepromDataParser.hpp" + +namespace dai { +namespace utility { + +std::vector split(const std::string& s, char delimiter) { + std::vector tokens; + size_t start = 0; + size_t end = s.find(delimiter); + + while(end != std::string::npos) { + tokens.push_back(s.substr(start, end - start)); + start = end + 1; + end = s.find(delimiter, start); + } + + tokens.push_back(s.substr(start, end)); + + return tokens; +} + +std::string parseProductName(EepromData eeprom, EepromData eepromFactory) { + std::string productName; + if((productName = eepromFactory.productName).empty()) { + if((productName = eeprom.productName).empty()) { + productName = eeprom.boardName; + } + } + + // Convert to device naming from display/product naming + std::transform(productName.begin(), productName.end(), productName.begin(), [](int c) { return std::toupper(c); }); + std::replace(productName.begin(), productName.end(), ' ', '-'); + + // Handle some known legacy cases + if(productName == "BW1098OBC") { + productName = "OAK-D"; + } else if(productName == "DM2097") { + productName = "OAK-D-CM4-POE"; + } else if(productName == "BW1097") { + productName = "OAK-D-CM3"; + } + + return productName; +} + +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory) { + std::string deviceName; + if((deviceName = eepromFactory.deviceName).empty()) { + if((deviceName = eeprom.deviceName).empty()) { + // Constant skuDiff array + const std::array skuDiff = {"AF", "FF", "97", "9782", "OV9782"}; + + // Parse productName and use that to generate device name + deviceName = parseProductName(eeprom, eepromFactory); + + // Regenerate from tokens + auto tokens = split(deviceName, '-'); + deviceName = ""; + for(unsigned int i = 0; i < tokens.size(); i++) { + const auto& token = tokens[i]; + + // check if token has to be removed + bool skipToken = false; + for(const auto& d : skuDiff) { + if(token == d) { + skipToken = true; + break; + } + } + if(skipToken) continue; + + if(i != 0) deviceName += "-"; + deviceName += token; + } + + // Return generated deviceName + return deviceName; + } + } + + return deviceName; +} + +} // namespace utility +} // namespace dai diff --git a/src/utility/EepromDataParser.hpp b/src/utility/EepromDataParser.hpp new file mode 100644 index 000000000..0bab9f574 --- /dev/null +++ b/src/utility/EepromDataParser.hpp @@ -0,0 +1,29 @@ +#pragma once + +#include "depthai-shared/common/EepromData.hpp" + +namespace dai +{ +namespace utility +{ + +/// @brief Splits given string by delimiter +/// @param s string to split +/// @param delimiter character by which to split +/// @return vector of split strings +std::vector split(const std::string& s, char delimiter); + +/// @brief Parses product name from given EepromData combination +/// @param eeprom EepromData containing fields to parse product name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning product name or empty +std::string parseProductName(EepromData eeprom, EepromData eepromFactory = {}); + +/// @brief Parses device name from given EepromData combination +/// @param eeprom EepromData containing fields to parse device name from +/// @param eepromFactory Additional factory eeprom which takes precedence when parsing +/// @return string contaning device name or empty +std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory = {}); + +} // namespace utility +} // namespace dai diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index 931cb7f5c..5225ed6aa 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -4,6 +4,7 @@ #include // project +#include "build/config.hpp" #include "build/version.hpp" #include "utility/Environment.hpp" #include "utility/Logging.hpp" @@ -81,8 +82,12 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav if(additionalInfo != nullptr && additionalInfo[0] != '\0') { logger::debug("{}", additionalInfo); } - logger::debug( - "Library information - version: {}, commit: {} from {}, build: {}", build::VERSION, build::COMMIT, build::COMMIT_DATETIME, build::BUILD_DATETIME); + logger::debug("Library information - version: {}, commit: {} from {}, build: {}, libusb enabled: {}", + build::VERSION, + build::COMMIT, + build::COMMIT_DATETIME, + build::BUILD_DATETIME, + build::HAVE_LIBUSB_SUPPORT); // Executed at library load time @@ -104,10 +109,13 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav logger::debug("Initialize failed - {}", errorMsg); throw std::runtime_error(errorMsg); } - // Check that USB protocol is available + + // Check that USB protocol is available, IFF libusb is enabled +#ifdef DEPTHAI_ENABLE_LIBUSB if(!XLinkIsProtocolInitialized(X_LINK_USB_VSC)) { logger::warn("USB protocol not available - {}", ERROR_MSG_USB_TIP); } +#endif // Enable Global XLink profiling XLinkProfStart(); diff --git a/src/utility/Path.cpp b/src/utility/Path.cpp index f7b625530..fe0b970e8 100644 --- a/src/utility/Path.cpp +++ b/src/utility/Path.cpp @@ -10,13 +10,13 @@ namespace dai { std::wstring Path::convert_utf8_to_wide(const std::string& utf8string) { - //#pragma warning(suppress : 4996) + // #pragma warning(suppress : 4996) std::wstring_convert> converter; return converter.from_bytes(utf8string); } std::string Path::u8string() const { - //#pragma warning(suppress : 4996) + // #pragma warning(suppress : 4996) std::wstring_convert> converter; return converter.to_bytes(_nativePath); } diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index 3e41fac1d..61fe0c5b7 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -116,7 +116,7 @@ std::vector XLinkConnection::getAllConnectedDevices(XLinkDeviceState std::vector devices; unsigned int numdev = 0; - std::array deviceDescAll = {}; + std::array deviceDescAll = {}; deviceDesc_t suitableDevice = {}; suitableDevice.protocol = getDefaultProtocol(); suitableDevice.platform = X_LINK_ANY_PLATFORM; diff --git a/src/xlink/XLinkStream.cpp b/src/xlink/XLinkStream.cpp index fa9393dee..107012ab5 100644 --- a/src/xlink/XLinkStream.cpp +++ b/src/xlink/XLinkStream.cpp @@ -54,7 +54,7 @@ XLinkStream::~XLinkStream() { } } -StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length} { +StreamPacketDesc::StreamPacketDesc(StreamPacketDesc&& other) noexcept : streamPacketDesc_t{other.data, other.length, other.tRemoteSent, other.tReceived} { other.data = nullptr; other.length = 0; } @@ -63,6 +63,8 @@ StreamPacketDesc& StreamPacketDesc::operator=(StreamPacketDesc&& other) noexcept if(this != &other) { data = std::exchange(other.data, nullptr); length = std::exchange(other.length, 0); + tRemoteSent = std::exchange(other.tRemoteSent, {}); + tReceived = std::exchange(other.tReceived, {}); } return *this; } @@ -98,12 +100,28 @@ void XLinkStream::read(std::vector& data) { data = std::vector(packet.data, packet.data + packet.length); } +void XLinkStream::read(std::vector& data, XLinkTimespec& timestampReceived) { + StreamPacketDesc packet; + const auto status = XLinkReadMoveData(streamId, &packet); + if(status != X_LINK_SUCCESS) { + throw XLinkReadError(status, streamName); + } + data = std::vector(packet.data, packet.data + packet.length); + timestampReceived = packet.tReceived; +} + std::vector XLinkStream::read() { std::vector data; read(data); return data; } +std::vector XLinkStream::read(XLinkTimespec& timestampReceived) { + std::vector data; + read(data, timestampReceived); + return data; +} + StreamPacketDesc XLinkStream::readMove() { StreamPacketDesc packet; const auto status = XLinkReadMoveData(streamId, &packet); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 21260e2f8..381072b80 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -107,8 +107,9 @@ function(dai_add_test test_name test_src) set(depthai_dll_libraries "$") endif() add_custom_command(TARGET ${test_name} POST_BUILD COMMAND - ${CMAKE_COMMAND} -E copy_if_different ${depthai_dll_libraries} $ + "$<$:${CMAKE_COMMAND};-E;copy_if_different;${depthai_dll_libraries};$>" COMMAND_EXPAND_LISTS + VERBATIM ) endif() endfunction() @@ -216,6 +217,9 @@ dai_test_compile_definitions(openvino_blob_test PRIVATE # Bootloader configuration tests dai_add_test(bootloader_config_test src/bootloader_config_test.cpp) +# Eeprom naming parsing tests +dai_add_test(naming_test src/naming_test.cpp) + # Device USB Speed and serialization macros test dai_add_test(device_usbspeed_test src/device_usbspeed_test.cpp CONFORMING) dai_add_test(device_usbspeed_test_17 src/device_usbspeed_test.cpp CONFORMING CXX_STANDARD 17) diff --git a/tests/src/device_usbspeed_test.cpp b/tests/src/device_usbspeed_test.cpp index d5d99b7a5..8605b1425 100644 --- a/tests/src/device_usbspeed_test.cpp +++ b/tests/src/device_usbspeed_test.cpp @@ -49,5 +49,38 @@ TEST_CASE("UsbSpeed::SUPER_PLUS") { dai::Pipeline p; makeInfo(p); dai::Device d(p, dai::UsbSpeed::SUPER_PLUS); + + verifyInfo(d); +} + +TEST_CASE("Pipeline config usb speed == SUPER") { + dai::Pipeline p; + makeInfo(p); + + dai::DeviceBase::Config cfg; + cfg.board.usb.maxSpeed = dai::UsbSpeed::SUPER; + + p.setBoardConfig(cfg.board); + + dai::Device d(p); + + CHECK(d.getUsbSpeed() == dai::UsbSpeed::SUPER); + + verifyInfo(d); +} + +TEST_CASE("Pipeline config usb speed == HIGH") { + dai::Pipeline p; + makeInfo(p); + + dai::DeviceBase::Config cfg; + cfg.board.usb.maxSpeed = dai::UsbSpeed::HIGH; + + p.setBoardConfig(cfg.board); + + dai::Device d(p); + + CHECK(d.getUsbSpeed() == dai::UsbSpeed::HIGH); + verifyInfo(d); } diff --git a/tests/src/naming_test.cpp b/tests/src/naming_test.cpp new file mode 100644 index 000000000..6abd99229 --- /dev/null +++ b/tests/src/naming_test.cpp @@ -0,0 +1,113 @@ +#include + +#include "../../src/utility/EepromDataParser.hpp" + +struct ProductDevice { + std::string oldProductName, productName, deviceName; +}; +std::vector productToDeviceNames = { + {"OAK-D LR", "OAK-D-LR", "OAK-D-LR"}, + {"OAK-D", "OAK-D", "OAK-D"}, + {"OAK-FFC 1P PoE", "OAK-FFC-1P-POE", "OAK-FFC-1P-POE"}, + {"OAK-FFC 4P", "OAK-FFC-4P", "OAK-FFC-4P"}, + {"OAK-FFC 3P", "OAK-FFC-3P", "OAK-FFC-3P"}, + {"OAK-D CM4", "OAK-D-CM4", "OAK-D-CM4"}, + {"OAK-D SR", "OAK-D-SR", "OAK-D-SR"}, + {"OAK-D PoE AF", "OAK-D-POE-AF", "OAK-D-POE"}, + {"OAK-D CM4 PoE", "OAK-D-CM4-POE", "OAK-D-CM4-POE"}, + {"rae", "RAE", "RAE"}, + {"OAK-FFC 6P", "OAK-FFC-6P", "OAK-FFC-6P"}, + {"OAK-D Lite", "OAK-D-LITE", "OAK-D-LITE"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D Pro AF", "OAK-D-PRO-AF", "OAK-D-PRO"}, + {"OAK-D Pro FF 97", "OAK-D-PRO-FF-97", "OAK-D-PRO"}, + {"OAK-D Pro FF", "OAK-D-PRO-FF", "OAK-D-PRO"}, + {"OAK-D Pro W 97", "OAK-D-PRO-W-97", "OAK-D-PRO-W"}, + {"OAK-D Pro W OV9782", "OAK-D-PRO-W-OV9782", "OAK-D-PRO-W"}, + {"OAK-D Pro W", "OAK-D-PRO-W", "OAK-D-PRO-W"}, + {"OAK-D S2 AF", "OAK-D-S2-AF", "OAK-D-S2"}, + {"OAK-D S2 FF", "OAK-D-S2-FF", "OAK-D-S2"}, + {"OAK-D W", "OAK-D-W", "OAK-D-W"}, + {"OAK-D W 97", "OAK-D-W-97", "OAK-D-W"}, + {"OAK-D SR PoE", "OAK-D-SR-POE", "OAK-D-SR-POE"}, + {"OAK-FFC-4P PoE", "OAK-FFC-4P-POE", "OAK-FFC-4P-POE"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-1 AF", "OAK-1-AF", "OAK-1"}, + {"OAK-1-FF 97", "OAK-1-FF-97", "OAK-1"}, + {"OAK-1 FF", "OAK-1-FF", "OAK-1"}, + {"OAK-1 Lite FF", "OAK-1-LITE-FF", "OAK-1-LITE"}, + {"OAK-1 Lite W", "OAK-1-LITE-W", "OAK-1-LITE-W"}, + {"OAK-1 Max", "OAK-1-MAX", "OAK-1-MAX"}, + {"OAK-1 W 97", "OAK-1-W-97", "OAK-1-W"}, + {"OAK-1 W", "OAK-1-W", "OAK-1-W"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D S2 PoE AF", "OAK-D-S2-POE-AF", "OAK-D-S2-POE"}, + {"OAK-D S2 PoE FF", "OAK-D-S2-POE-FF", "OAK-D-S2-POE"}, + {"OAK-D W PoE", "OAK-D-W-POE", "OAK-D-W-POE"}, + {"OAK-D Pro PoE AF", "OAK-D-PRO-POE-AF", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF 97", "OAK-D-PRO-POE-FF-97", "OAK-D-PRO-POE"}, + {"OAK-D Pro PoE FF", "OAK-D-PRO-POE-FF", "OAK-D-PRO-POE"}, + {"OAK-D Pro W PoE", "OAK-D-PRO-W-POE", "OAK-D-PRO-W-POE"}, + {"OAK-D Pro W PoE 97", "OAK-D-PRO-W-POE-97", "OAK-D-PRO-W-POE"}, + {"OAK-D W PoE 97", "OAK-D-W-POE-97", "OAK-D-W-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 W PoE 9782", "OAK-1-W-POE-9782", "OAK-1-W-POE"}, + {"OAK-1 W PoE", "OAK-1-W-POE", "OAK-1-W-POE"}, + {"OAK-1 PoE AF", "OAK-1-POE-AF", "OAK-1-POE"}, + {"OAK-1 PoE FF", "OAK-1-POE-FF", "OAK-1-POE"}, + + // Special cases, resolved by modifying eeprom instead + // {"OAK-D PoE C22", "OAK-D-POE-C22", "OAK-D-POE"}, + // {"", "OAK-D-CM4-POE-C11", "OAK-D-CM4-POE"}, + // {"", "OAK-D-CM4-POE-C24", "OAK-D-CM4-POE"}, + //{"OAK-D Pro AF PB", "OAK-D-PRO-AF-PB", "OAK-D-PRO"}, + // {"OAK-D Pro FF C13", "OAK-D-PRO-FF-C13", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-C17", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#1", "OAK-D-PRO"}, + // {"", "OAK-D-PRO-FF-PB-FF#2", "OAK-D-PRO"}, + // {"OAK-D Pro W C06", "OAK-D-PRO-W-C06", "OAK-D-PRO-W"}, + // {"OAK-D Pro FF", "OAK-D-PRO-W-C16", "OAK-D-PRO-W"}, + // {"", "OAK-D-W-C15", "OAK-D-W"}, + // {"", "OAK-D-PRO-W-DEV", "OAK-D-PRO-W-DEV"}, + // {"", "OAK-1-LITE-C05", "OAK-1-LITE"}, + // {"OAK-1 AF", "OAK-1-AF-C20", "OAK-1"}, + // {"OAK-D Pro PoE AF C18", "OAK-D-PRO-POE-AF-C18", "OAK-D-PRO-POE-C18"}, + // {"OAK-D Pro W PoE C01", "OAK-D-PRO-W-POE-C01", "OAK-D-PRO-W-POE-C01"}, + +}; + +TEST_CASE("parsing") { + for(size_t i = 0; i < productToDeviceNames.size(); i++) { + INFO("Testing with iteration number: " << i); + + const auto& pd = productToDeviceNames[i]; + dai::EepromData data; + data.productName = pd.productName; + + // Test parsing of device name + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + data.productName = pd.oldProductName; + REQUIRE(pd.productName == dai::utility::parseProductName(data)); + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + + // Test parsing directly to device name + data.deviceName = pd.deviceName; + REQUIRE(pd.deviceName == dai::utility::parseDeviceName(data)); + } +} \ No newline at end of file