diff --git a/CHANGELOG.rst b/CHANGELOG.rst index a89140436..cd4433152 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -1,6 +1,33 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package depthai ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.21.0 (2023-04-03) +----------- +* Improved x/y accuracy for SpatialLocationCalculator/SpatialDetectionNetwork +* Support for median and mode, default changed to median in SpatialLocationCalculator/SpatialDetectionNetwork +* Multi stereo support, ability to run stereo between any 2 calibrated cameras +* Support for LEFT/RIGHT alignment in stereo node +* Support to invalidate edge pixels: setNumInvalidateEdgePixels in Stereo Node +* BrightnessFilter - If the input frame pixel is too dark or too bright, the disparity will be invalidated. Default pixels with value 0 are invalidated in Stereo Node +* Added disparityToDepthUseSpecTranslation, rectificationUseSpecTranslation, and depthAlignmentUseSpecTranslation options for advanced usage in Stereo Node +* Fix for RGB-depth alignment when RGB is configured to 12 MP +* Crash dump support - support to retrieve crash context from the device which can be shared with developers +* Configurable 3A fps - setIsp3aFps +* IMU - support to retrieve connected IMU type, and firmware version. Refactored firmware update API +* BMI270 - enable interrupt mode, timestamps are more consistent now +* BNO086* - fix for sequence number +* 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 +* HW sync (trigger mode) enabled for OAK-D-LR, for cameras with matching FPS +* FW: fix for UART0 / '/dev/ttyS0' init failure in Script node +* POE power cycle fix - in rare occasions POE devices got stuck after reboot, requiring a manual power cycle +* [XLink] Increased max number of links from 32 to 64 +* Update FW with performance metrics when DEPTHAI_LEVEL=info is enabled +* Handle EEPROM boardOptions bit 7 for separate I2C on L/R cameras +* Contributors: Alex Bougdan, Szabolcs Gergely, Martin Peterlin + 2.20.2 (2023-01-31) ----------- * Fix for ColorCamera at high resolution while using isp scaling diff --git a/CMakeLists.txt b/CMakeLists.txt index 615b377f1..bb044b54f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -45,7 +45,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.20.2" LANGUAGES CXX C) +project(depthai VERSION "2.21.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) diff --git a/README.md b/README.md index 820a65443..62564c22e 100644 --- a/README.md +++ b/README.md @@ -47,6 +47,29 @@ cmake -S. -Bbuild -D'BUILD_SHARED_LIBS=ON' cmake --build build ``` + +### Android + +Android is supported to some extent but not actively pursued nor tested. PRs with any improvements are welcome. + +Steps: + + - Install Android NDK (for example via Android Studio). + - Set the NDK path: +``` +export ANDROID_HOME=$HOME/.local/lib/Android +export PATH=$PATH:$ANDROID_HOME/emulator:$ANDROID_HOME/platform-tools +export NDK=$ANDROID_HOME/ndk/23.1.7779620/ # Check version +``` + - Ensure a recent version of cmake (apt version is outdated, install snap install cmake --classic) + - Run cmake, set your ABI and Platform as needed: + +``` +cmake -S. -Bbuild -DCMAKE_TOOLCHAIN_FILE=$NDK/build/cmake/android.toolchain.cmake -DANDROID_ABI=armeabi-v7a -DANDROID_PLATFORM=android-25 +cmake --build build +``` + + ## Running examples To build the examples configure with following option added diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index b2897551c..c44eec89a 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 "8c3d6ac1c77b0bf7f9ea6fd4d962af37663d2fbd") +set(DEPTHAI_DEVICE_SIDE_COMMIT "57ca2c171f6ef53cb83fbbc3aabfe512c67796ce") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index 6e303798d..dc189ea09 100644 --- a/cmake/Hunter/config.cmake +++ b/cmake/Hunter/config.cmake @@ -8,8 +8,8 @@ hunter_config( hunter_config( XLink VERSION "luxonis-2021.4.2-develop" - URL "https://github.com/luxonis/XLink/archive/1ef2f960eec66540891434c9a3341c11e66e4360.tar.gz" - SHA1 "23641bb9ae698d0e016abcce349094a38577838b" + URL "https://github.com/luxonis/XLink/archive/b7c3aca2ba8b9d598be886a8076a875b50f5184f.tar.gz" + SHA1 "6c19757c6fe6871a9f40688871edbfc6f1e939ee" ) hunter_config( @@ -100,8 +100,8 @@ hunter_config( hunter_config( Catch2 VERSION "2.13.7" - URL "https://github.com/catchorg/Catch2/archive/refs/tags/v2.13.7.tar.gz" - SHA1 "fa8f14ccf852413d3c6d3999145ada934d37d773" + URL "https://github.com/catchorg/Catch2/archive/refs/tags/v3.2.1.tar.gz" + SHA1 "acfba7f71cbbbbf60bc1bc4c0e3efca4a9c70df7" ) # ZLib - Luxonis fix for alias on imported target for old CMake versions diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 8b90a8900..97b31f65c 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -32,6 +32,10 @@ function(dai_add_example example_name example_src enable_test) add_executable(${example_name} ${example_src}) add_default_flags(${example_name} LEAN) target_link_libraries(${example_name} PRIVATE utility depthai::opencv ${OpenCV_LIBS} Threads::Threads) + # Set compiler features (c++14), and disables extensions (g++14) + set_property(TARGET ${example_name} PROPERTY CXX_STANDARD 14) + set_property(TARGET ${example_name} PROPERTY CXX_STANDARD_REQUIRED ON) + set_property(TARGET ${example_name} PROPERTY CXX_EXTENSIONS OFF) # Add sanitizers for example if(COMMAND add_sanitizers) @@ -359,3 +363,6 @@ dai_add_example(apriltag_rgb AprilTag/apriltag_rgb.cpp ON) # DetectionParser dai_add_example(detection_parser NeuralNetwork/detection_parser.cpp ON) target_compile_definitions(detection_parser PRIVATE BLOB_PATH="${mobilenet_blob}") + +# DetectionParser +dai_add_example(crash_report CrashReport/crash_report.cpp OFF) diff --git a/examples/CrashReport/crash_report.cpp b/examples/CrashReport/crash_report.cpp new file mode 100644 index 000000000..4881a18b6 --- /dev/null +++ b/examples/CrashReport/crash_report.cpp @@ -0,0 +1,41 @@ +#include +#include + +// Includes common necessary includes for development using depthai library +#include "depthai/depthai.hpp" + +static bool fileExists(dai::Path path) { + std::ifstream file(path); + return file.is_open(); +} + +int main() { + using namespace std; + + // Connect to device and start pipeline + dai::Device device; + if(device.hasCrashDump()) { + auto crashDump = device.getCrashDump(); + std::string commitHash = crashDump.depthaiCommitHash; + std::string deviceId = crashDump.deviceId; + + auto json = crashDump.serializeToJson(); + + for(int i = 0;; i++) { + dai::Path destPath = "crashDump_" + to_string(i) + "_" + deviceId + "_" + commitHash + ".json"; + if(fileExists(destPath)) continue; + + std::ofstream ob(destPath); + ob << std::setw(4) << json << std::endl; + + std::cout << "Crash dump found on your device!" << std::endl; + std::cout << "Saved to " << destPath.string() << std::endl; + std::cout << "Please report to developers!" << std::endl; + break; + } + } else { + std::cout << "There was no crash dump found on your device!" << std::endl; + } + + return 0; +} \ No newline at end of file diff --git a/examples/FeatureTracker/feature_tracker.cpp b/examples/FeatureTracker/feature_tracker.cpp index adc8647bb..422128801 100644 --- a/examples/FeatureTracker/feature_tracker.cpp +++ b/examples/FeatureTracker/feature_tracker.cpp @@ -72,9 +72,7 @@ class FeatureTrackerDrawer { } } - FeatureTrackerDrawer(std::string trackbarName, std::string windowName) { - this->trackbarName = trackbarName; - this->windowName = windowName; + FeatureTrackerDrawer(std::string trackbarName, std::string windowName) : trackbarName(trackbarName), windowName(windowName) { cv::namedWindow(windowName.c_str()); cv::createTrackbar(trackbarName.c_str(), windowName.c_str(), &trackedFeaturesPathLength, maxTrackedFeaturesPathLength, nullptr); } diff --git a/examples/IMU/imu_firmware_update.cpp b/examples/IMU/imu_firmware_update.cpp index aaa0bb380..e95007bd6 100644 --- a/examples/IMU/imu_firmware_update.cpp +++ b/examples/IMU/imu_firmware_update.cpp @@ -11,6 +11,14 @@ int main() { using namespace std; using namespace std::chrono; + dai::Device device; + + auto imuType = device.getConnectedIMU(); + auto imuFirmwareVersion = device.getIMUFirmwareVersion(); + auto embeddedIMUFirmwareVersion = device.getEmbeddedIMUFirmwareVersion(); + std::cout << "IMU type: " << imuType << " firmware version: " << imuFirmwareVersion + << " embedded firmware version: " << embeddedIMUFirmwareVersion << std::endl; + std::cout << "Warning! Flashing IMU firmware can potentially soft brick your device and should be done with caution." << std::endl; std::cout << "Do not unplug your device while the IMU firmware is flashing." << std::endl; std::cout << "Type 'y' and press enter to proceed, otherwise exits: "; @@ -20,68 +28,26 @@ int main() { return -1; } - // Create pipeline - dai::Pipeline pipeline; - - // Define sources and outputs - auto imu = pipeline.create(); - auto xlinkOut = pipeline.create(); - - xlinkOut->setStreamName("imu"); - - // enable ACCELEROMETER_RAW at 500 hz rate - imu->enableIMUSensor(dai::IMUSensor::ACCELEROMETER_RAW, 500); - // enable GYROSCOPE_RAW at 400 hz rate - imu->enableIMUSensor(dai::IMUSensor::GYROSCOPE_RAW, 400); - // it's recommended to set both setBatchReportThreshold and setMaxBatchReports to 20 when integrating in a pipeline with a lot of input/output connections - // above this threshold packets will be sent in batch of X, if the host is not blocked and USB bandwidth is available - imu->setBatchReportThreshold(1); - // maximum number of IMU packets in a batch, if it's reached device will block sending until host can receive it - // if lower or equal to batchReportThreshold then the sending is always blocking on device - // useful to reduce device's CPU load and number of lost packets, if CPU load is high on device side due to multiple nodes - imu->setMaxBatchReports(10); - - // Link plugins IMU -> XLINK - imu->out.link(xlinkOut->input); - - imu->enableFirmwareUpdate(true); - - // Pipeline is defined, now we can connect to the device - dai::Device d(pipeline); - - bool firstTs = false; - - auto imuQueue = d.getOutputQueue("imu", 50, false); - auto baseTs = std::chrono::time_point(); + auto started = device.startIMUFirmwareUpdate(); + if(!started) { + std::cout << "Couldn't start IMU firmware update" << std::endl; + return 1; + } while(true) { - auto imuData = imuQueue->get(); - - auto imuPackets = imuData->packets; - for(auto& imuPacket : imuPackets) { - auto& acceleroValues = imuPacket.acceleroMeter; - auto& gyroValues = imuPacket.gyroscope; - - auto acceleroTs1 = acceleroValues.getTimestampDevice(); - auto gyroTs1 = gyroValues.getTimestampDevice(); - if(!firstTs) { - baseTs = std::min(acceleroTs1, gyroTs1); - firstTs = true; + bool fwUpdateFinished; + float percentage; + std::tie(fwUpdateFinished, percentage) = device.getIMUFirmwareUpdateStatus(); + std::cout << "IMU FW update status: " << std::setprecision(1) << percentage << std::endl; + if(fwUpdateFinished) { + if(percentage == 100) { + std::cout << "Firmware update successful!" << std::endl; + } else { + std::cout << "Firmware update failed!" << std::endl; } - - auto acceleroTs = acceleroTs1 - baseTs; - auto gyroTs = gyroTs1 - baseTs; - - printf("Accelerometer timestamp: %ld ms\n", static_cast(duration_cast(acceleroTs).count())); - printf("Accelerometer [m/s^2]: x: %.3f y: %.3f z: %.3f \n", acceleroValues.x, acceleroValues.y, acceleroValues.z); - printf("Gyroscope timestamp: %ld ms\n", static_cast(duration_cast(gyroTs).count())); - printf("Gyroscope [rad/s]: x: %.3f y: %.3f z: %.3f \n", gyroValues.x, gyroValues.y, gyroValues.z); - } - - int key = cv::waitKey(1); - if(key == 'q') { - return 0; + break; } + std::this_thread::sleep_for(1s); } return 0; diff --git a/examples/SpatialDetection/spatial_location_calculator.cpp b/examples/SpatialDetection/spatial_location_calculator.cpp index d838daab8..5e7cd9c43 100644 --- a/examples/SpatialDetection/spatial_location_calculator.cpp +++ b/examples/SpatialDetection/spatial_location_calculator.cpp @@ -49,6 +49,8 @@ int main() { dai::SpatialLocationCalculatorConfigData config; config.depthThresholds.lowerThreshold = 100; config.depthThresholds.upperThreshold = 10000; + auto calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MEDIAN; + config.calculationAlgorithm = calculationAlgorithm; config.roi = dai::Rect(topLeft, bottomRight); spatialDataCalculator->inputConfig.setWaitForMessage(false); @@ -144,12 +146,38 @@ int main() { newConfig = true; } break; + case '1': + calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MEAN; + newConfig = true; + std::cout << "Switching calculation algorithm to MEAN!" << std::endl; + break; + case '2': + calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MIN; + newConfig = true; + std::cout << "Switching calculation algorithm to MIN!" << std::endl; + break; + case '3': + calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MAX; + newConfig = true; + std::cout << "Switching calculation algorithm to MAX!" << std::endl; + break; + case '4': + calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MODE; + newConfig = true; + std::cout << "Switching calculation algorithm to MODE!" << std::endl; + break; + case '5': + calculationAlgorithm = dai::SpatialLocationCalculatorAlgorithm::MEDIAN; + newConfig = true; + std::cout << "Switching calculation algorithm to MEDIAN!" << std::endl; + break; default: break; } if(newConfig) { config.roi = dai::Rect(topLeft, bottomRight); + config.calculationAlgorithm = calculationAlgorithm; dai::SpatialLocationCalculatorConfig cfg; cfg.addROI(config); spatialCalcConfigInQueue->send(cfg); diff --git a/examples/StereoDepth/stereo_depth_video.cpp b/examples/StereoDepth/stereo_depth_video.cpp index af71ea714..e30e76051 100644 --- a/examples/StereoDepth/stereo_depth_video.cpp +++ b/examples/StereoDepth/stereo_depth_video.cpp @@ -98,7 +98,6 @@ int main() { cv::imshow("right", right->getFrame()); if(withDepth) { - // Note: in some configurations (if depth is enabled), disparity may output garbage data auto disparity = dispQueue->get(); cv::Mat disp(disparity->getCvFrame()); disp.convertTo(disp, CV_8UC1, disparityMultiplier); // Extend disparity range diff --git a/include/depthai/device/DataQueue.hpp b/include/depthai/device/DataQueue.hpp index 607282333..e27adba05 100644 --- a/include/depthai/device/DataQueue.hpp +++ b/include/depthai/device/DataQueue.hpp @@ -43,6 +43,10 @@ class DataOutputQueue { /** * Check whether queue is closed + * + * @warning This function is thread-unsafe and may return outdated incorrect values. It is + * only meant for use in simple single-threaded code. Well written code should handle + * exceptions when calling any DepthAI apis to handle hardware events and multithreaded use. */ bool isClosed() const; @@ -343,7 +347,7 @@ class DataInputQueue { std::atomic running{true}; std::string exceptionMessage; const std::string name; - std::size_t maxDataSize = device::XLINK_USB_BUFFER_MAX_SIZE; + std::atomic maxDataSize{device::XLINK_USB_BUFFER_MAX_SIZE}; public: DataInputQueue(const std::shared_ptr conn, @@ -355,6 +359,10 @@ class DataInputQueue { /** * Check whether queue is closed + * + * @warning This function is thread-unsafe and may return outdated incorrect values. It is + * only meant for use in simple single-threaded code. Well written code should handle + * exceptions when calling any DepthAI apis to handle hardware events and multithreaded use. */ bool isClosed() const; diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 1090f05b1..53467f3d4 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -26,11 +26,12 @@ #include "depthai/xlink/XLinkStream.hpp" // shared -#include "depthai-shared/common/CameraFeatures.hpp" #include "depthai-shared/common/ChipTemperature.hpp" #include "depthai-shared/common/CpuUsage.hpp" #include "depthai-shared/common/MemoryInfo.hpp" +#include "depthai-shared/datatype/RawIMUData.hpp" #include "depthai-shared/device/BoardConfig.hpp" +#include "depthai-shared/device/CrashDump.hpp" #include "depthai-shared/log/LogLevel.hpp" #include "depthai-shared/log/LogMessage.hpp" @@ -65,7 +66,7 @@ class DeviceBase { * Device specific configuration */ struct Config { - OpenVINO::Version version; + OpenVINO::Version version = OpenVINO::VERSION_UNIVERSAL; BoardConfig board; bool nonExclusiveMode = false; }; @@ -451,6 +452,16 @@ class DeviceBase { */ std::vector> getIrDrivers(); + /** + * Retrieves crash dump for debugging. + */ + dai::CrashDump getCrashDump(); + + /** + * Retrieves whether the is crash dump stored on device or not. + */ + bool hasCrashDump(); + /** * Add a callback for device logging. The callback will be called from a separate thread with the LogMessage being passed. * @@ -503,6 +514,47 @@ class DeviceBase { */ std::unordered_map getCameraSensorNames(); + /** + * Get connected IMU type + * + * @returns IMU type + */ + std::string getConnectedIMU(); + + /** + * Get connected IMU firmware version + * + * @returns IMU firmware version + */ + dai::Version getIMUFirmwareVersion(); + + /** + * Get embedded IMU firmware version to which IMU can be upgraded + * + * @returns Get embedded IMU firmware version to which IMU can be upgraded. + */ + dai::Version getEmbeddedIMUFirmwareVersion(); + + /** + * Starts IMU firmware update asynchronously only if IMU node is not running. + * If current firmware version is the same as embedded firmware version then it's no-op. Can be overridden by forceUpdate parameter. + * State of firmware update can be monitored using getIMUFirmwareUpdateStatus API. + * + * @param forceUpdate Force firmware update or not. Will perform FW update regardless of current version and embedded firmware version. + * + * @returns Returns whether firmware update can be started. Returns false if IMU node is started. + */ + bool startIMUFirmwareUpdate(bool forceUpdate = false); + + /** + * Get IMU firmware update status + * + * @returns Whether IMU firmware update is done and last firmware update progress as percentage. + * return value true and 100 means that the update was successful + * return value true and other than 100 means that the update failed + */ + std::tuple getIMUFirmwareUpdateStatus(); + /** * Retrieves current DDR memory information from device * @@ -699,6 +751,10 @@ class DeviceBase { /** * Is the device already closed (or disconnected) + * + * @warning This function is thread-unsafe and may return outdated incorrect values. It is + * only meant for use in simple single-threaded code. Well written code should handle + * exceptions when calling any DepthAI apis to handle hardware events and multithreaded use. */ bool isClosed() const; @@ -724,11 +780,6 @@ class DeviceBase { */ void tryStartPipeline(const Pipeline& pipeline); - /** - * throws an error if the device has been closed or the watchdog has died - */ - void checkClosed() const; - /** * Allows the derived classes to handle custom setup for starting the pipeline * @@ -781,9 +832,6 @@ class DeviceBase { std::mutex lastWatchdogPingTimeMtx; std::chrono::steady_clock::time_point lastWatchdogPingTime; - // RPC stream - std::unique_ptr rpcStream; - // closed mutable std::mutex closedMtx; bool closed{false}; diff --git a/include/depthai/device/DeviceBootloader.hpp b/include/depthai/device/DeviceBootloader.hpp index 3baab110e..0c34d0957 100644 --- a/include/depthai/device/DeviceBootloader.hpp +++ b/include/depthai/device/DeviceBootloader.hpp @@ -211,6 +211,14 @@ class DeviceBootloader { */ DeviceBootloader(const DeviceInfo& devInfo, const dai::Path& pathToBootloader, bool allowFlashingBootloader = false); + /** + * Connects to device with specified name/device id + * + * @param nameOrDeviceId Creates DeviceInfo with nameOrDeviceId to connect to + * @param allowFlashingBootloader Set to true to allow flashing the devices bootloader. Defaults to false + */ + DeviceBootloader(std::string nameOrDeviceId, bool allowFlashingBootloader = false); + /** * @brief Destroy the Device Bootloader object * @@ -458,6 +466,10 @@ class DeviceBootloader { /** * Is the device already closed (or disconnected) + * + * @warning This function is thread-unsafe and may return outdated incorrect values. It is + * only meant for use in simple single-threaded code. Well written code should handle + * exceptions when calling any DepthAI apis to handle hardware events and multithreaded use. */ bool isClosed() const; @@ -466,7 +478,6 @@ class DeviceBootloader { // private methods void init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl::optional type, bool allowBlFlash); - void checkClosed() const; template bool sendRequest(const T& request); template diff --git a/include/depthai/pipeline/Pipeline.hpp b/include/depthai/pipeline/Pipeline.hpp index 6eb46f440..a10a3cf5c 100644 --- a/include/depthai/pipeline/Pipeline.hpp +++ b/include/depthai/pipeline/Pipeline.hpp @@ -41,6 +41,8 @@ class PipelineImpl { Device::Config getDeviceConfig() const; void setCameraTuningBlobPath(const dai::Path& path); void setXLinkChunkSize(int sizeBytes); + void setSippBufferSize(int sizeBytes); + void setSippDmaBufferSize(int sizeBytes); void setBoardConfig(BoardConfig board); BoardConfig getBoardConfig() const; @@ -265,6 +267,28 @@ class Pipeline { impl()->setXLinkChunkSize(sizeBytes); } + /** + * SIPP (Signal Image Processing Pipeline) internal memory pool. + * SIPP is a framework used to schedule HW filters, e.g. ISP, Warp, Median filter etc. + * Changing the size of this pool is meant for advanced use cases, pushing the limits of the HW. + * By default memory is allocated in high speed CMX memory. Setting to 0 will allocate in DDR 256 kilobytes. + * Units are bytes. + */ + void setSippBufferSize(int sizeBytes) { + impl()->setSippBufferSize(sizeBytes); + } + + /** + * SIPP (Signal Image Processing Pipeline) internal DMA memory pool. + * SIPP is a framework used to schedule HW filters, e.g. ISP, Warp, Median filter etc. + * Changing the size of this pool is meant for advanced use cases, pushing the limits of the HW. + * Memory is allocated in high speed CMX memory + * Units are bytes. + */ + void setSippDmaBufferSize(int sizeBytes) { + impl()->setSippDmaBufferSize(sizeBytes); + } + /// Checks whether a given OpenVINO version is compatible with the pipeline bool isOpenVINOVersionCompatible(OpenVINO::Version version) const { return impl()->isOpenVINOVersionCompatible(version); diff --git a/include/depthai/pipeline/datatype/StereoDepthConfig.hpp b/include/depthai/pipeline/datatype/StereoDepthConfig.hpp index ede7c7ef6..e709d1140 100644 --- a/include/depthai/pipeline/datatype/StereoDepthConfig.hpp +++ b/include/depthai/pipeline/datatype/StereoDepthConfig.hpp @@ -121,6 +121,13 @@ class StereoDepthConfig : public Buffer { */ StereoDepthConfig& setDisparityShift(int disparityShift); + /** + * Invalidate X amount of pixels at the edge of disparity frame. + * For right and center alignment X pixels will be invalidated from the right edge, + * for left alignment from the left edge. + */ + StereoDepthConfig& setNumInvalidateEdgePixels(int32_t numInvalidateEdgePixels); + /** * Get depth unit of depth map. */ diff --git a/include/depthai/pipeline/node/Camera.hpp b/include/depthai/pipeline/node/Camera.hpp index 93c216d5d..5ea4ec6b5 100644 --- a/include/depthai/pipeline/node/Camera.hpp +++ b/include/depthai/pipeline/node/Camera.hpp @@ -198,6 +198,15 @@ class Camera : public NodeCRTP { */ void setFps(float fps); + /** + * Isp 3A rate (auto focus, auto exposure, auto white balance, camera controls etc.). + * Default (0) matches the camera FPS, meaning that 3A is running on each frame. + * Reducing the rate of 3A reduces the CPU usage on CSS, but also increases the convergence rate of 3A. + * Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, + * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. + */ + void setIsp3aFps(int isp3aFps); + /** * Get rate at which camera should produce frames * @returns Rate in frames per second diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 9df071043..1e36cfba3 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -222,6 +222,16 @@ class ColorCamera : public NodeCRTP { */ void setFps(float fps); + /** + * Isp 3A rate (auto focus, auto exposure, auto white balance, camera controls etc.). + * Default (0) matches the camera FPS, meaning that 3A is running on each frame. + * Reducing the rate of 3A reduces the CPU usage on CSS, but also increases the convergence rate of 3A. + * Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, + * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. + + */ + void setIsp3aFps(int isp3aFps); + // Set events on which frames will be received void setFrameEventFilter(const std::vector& events); diff --git a/include/depthai/pipeline/node/MonoCamera.hpp b/include/depthai/pipeline/node/MonoCamera.hpp index af4be1bd2..7b1348ca8 100644 --- a/include/depthai/pipeline/node/MonoCamera.hpp +++ b/include/depthai/pipeline/node/MonoCamera.hpp @@ -117,6 +117,16 @@ class MonoCamera : public NodeCRTP { */ void setFps(float fps); + /** + * Isp 3A rate (auto focus, auto exposure, auto white balance, camera controls etc.). + * Default (0) matches the camera FPS, meaning that 3A is running on each frame. + * Reducing the rate of 3A reduces the CPU usage on CSS, but also increases the convergence rate of 3A. + * Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, + * but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing. + + */ + void setIsp3aFps(int isp3aFps); + /** * Get rate at which camera should produce frames * @returns Rate in frames per second diff --git a/include/depthai/pipeline/node/ObjectTracker.hpp b/include/depthai/pipeline/node/ObjectTracker.hpp index af94ece38..b1e76bb72 100644 --- a/include/depthai/pipeline/node/ObjectTracker.hpp +++ b/include/depthai/pipeline/node/ObjectTracker.hpp @@ -93,6 +93,11 @@ class ObjectTracker : public NodeCRTP { * Specifies SPI Bus number to use * @param id SPI Bus id */ - void setBusId(int id) { - properties.busId = id; + void setBusId(int busId) { + properties.busId = busId; } }; diff --git a/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp b/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp index 9427d8ee3..e782afa67 100644 --- a/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp +++ b/include/depthai/pipeline/node/SpatialDetectionNetwork.hpp @@ -94,6 +94,13 @@ class SpatialDetectionNetwork : public NodeCRTP { public: diff --git a/include/depthai/pipeline/node/StereoDepth.hpp b/include/depthai/pipeline/node/StereoDepth.hpp index 05c39f151..8976e2bdb 100644 --- a/include/depthai/pipeline/node/StereoDepth.hpp +++ b/include/depthai/pipeline/node/StereoDepth.hpp @@ -365,6 +365,34 @@ class StereoDepth : public NodeCRTP { * Units are pixels. */ void setFocalLength(float focalLength); + + /** + * Use baseline information for disparity to depth conversion from specs (design data) or from calibration. + * Default: true + */ + void setDisparityToDepthUseSpecTranslation(bool specTranslation); + + /** + * Obtain rectification matrices using spec translation (design data) or from calibration in calculations. + * Should be used only for debugging. + * Default: false + */ + void setRectificationUseSpecTranslation(bool specTranslation); + + /** + * Use baseline information for depth alignment from specs (design data) or from calibration. + * Default: true + */ + void setDepthAlignmentUseSpecTranslation(bool specTranslation); + + /** + * Free scaling parameter between 0 (when all the pixels in the undistorted image are valid) + * and 1 (when all the source image pixels are retained in the undistorted image). + * On some high distortion lenses, and/or due to rectification (image rotated) invalid areas may appear even with alpha=0, + * in these cases alpha < 0.0 helps removing invalid areas. + * See getOptimalNewCameraMatrix from opencv for more details. + */ + void setAlphaScaling(float alpha); }; } // namespace node diff --git a/include/depthai/pipeline/node/Warp.hpp b/include/depthai/pipeline/node/Warp.hpp index 3d9d16126..b86f608e3 100644 --- a/include/depthai/pipeline/node/Warp.hpp +++ b/include/depthai/pipeline/node/Warp.hpp @@ -80,7 +80,7 @@ class Warp : public NodeCRTP { /** * Specify which hardware warp engines to use - * @param ids Maximum frame size in bytes + * @param ids Which warp engines to use (0, 1, 2) */ void setHwIds(std::vector ids); /// Retrieve which hardware warp engines to use diff --git a/include/depthai/utility/LockingQueue.hpp b/include/depthai/utility/LockingQueue.hpp index a40179dfb..653a01f16 100644 --- a/include/depthai/utility/LockingQueue.hpp +++ b/include/depthai/utility/LockingQueue.hpp @@ -12,10 +12,7 @@ template class LockingQueue { public: LockingQueue() = default; - explicit LockingQueue(unsigned maxSize, bool blocking = true) { - this->maxSize = maxSize; - this->blocking = blocking; - } + explicit LockingQueue(unsigned maxSize, bool blocking = true) : maxSize(maxSize), blocking(blocking) {} void setMaxSize(unsigned sz) { // Lock first diff --git a/include/depthai/xlink/XLinkConnection.hpp b/include/depthai/xlink/XLinkConnection.hpp index 20753b70c..7c65a8c05 100644 --- a/include/depthai/xlink/XLinkConnection.hpp +++ b/include/depthai/xlink/XLinkConnection.hpp @@ -104,6 +104,10 @@ class XLinkConnection { /** * Is the connection already closed (or disconnected) + * + * @warning This function is thread-unsafe and may return outdated incorrect values. It is + * only meant for use in simple single-threaded code. Well written code should handle + * exceptions when calling any DepthAI apis to handle hardware events and multithreaded use. */ bool isClosed() const; @@ -116,7 +120,6 @@ class XLinkConnection { static std::string convertErrorCodeToString(XLinkError_t errorCode); void initDevice(const DeviceInfo& deviceToInit, XLinkDeviceState_t expectedState = X_LINK_BOOTED); - void checkClosed() const; bool bootDevice = true; bool bootWithPath = true; diff --git a/include/depthai/xlink/XLinkStream.hpp b/include/depthai/xlink/XLinkStream.hpp index f358fd943..47bc9ace2 100644 --- a/include/depthai/xlink/XLinkStream.hpp +++ b/include/depthai/xlink/XLinkStream.hpp @@ -7,6 +7,7 @@ #include #include #include +#include #include #include #include diff --git a/package.xml b/package.xml index 48b64e993..3555249ed 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ depthai - 2.20.2 + 2.21.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 32b30ef42..aa3e0564c 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit 32b30ef42cbe32137e3274031a049c401c46a2c1 +Subproject commit aa3e0564c0de3ef66cb6b240ff2b65ed3ed70aba diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index e6e2dd27a..729a778da 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -192,8 +192,8 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path camera.extrinsics.rotationMatrix[2][1] = temp; } -CalibrationHandler::CalibrationHandler(EepromData eepromData) { - this->eepromData = eepromData; +CalibrationHandler::CalibrationHandler(EepromData newEepromData) { + eepromData = newEepromData; } dai::EepromData CalibrationHandler::getEepromData() const { diff --git a/src/device/DataQueue.cpp b/src/device/DataQueue.cpp index 31d4e3807..3285df171 100644 --- a/src/device/DataQueue.cpp +++ b/src/device/DataQueue.cpp @@ -83,6 +83,10 @@ DataOutputQueue::DataOutputQueue(const std::shared_ptr conn, co }); } +// This function is thread-unsafe. The idea of "isClosed" is ephemerial and +// since there is no mutex lock, its state is outdated and invalid even before +// the logical NOT in this function. This calculated boolean then continues to degrade +// in validity as it is returned by value to the caller bool DataOutputQueue::isClosed() const { return !running; } @@ -173,7 +177,7 @@ bool DataOutputQueue::removeCallback(int callbackId) { DataInputQueue::DataInputQueue( const std::shared_ptr conn, const std::string& streamName, unsigned int maxSize, bool blocking, std::size_t maxDataSize) : queue(maxSize, blocking), name(streamName), maxDataSize(maxDataSize) { - // open stream with default XLINK_USB_BUFFER_MAX_SIZE write size + // open stream with maxDataSize write size XLinkStream stream(std::move(conn), name, maxDataSize + device::XLINK_MESSAGE_METADATA_MAX_SIZE); writingThread = std::thread([this, stream = std::move(stream)]() mutable { @@ -220,6 +224,10 @@ DataInputQueue::DataInputQueue( }); } +// This function is thread-unsafe. The idea of "isClosed" is ephemerial and +// since there is no mutex lock, its state is outdated and invalid even before +// the logical NOT in this function. This calculated boolean then continues to degrade +// in validity as it is returned by value to the caller bool DataInputQueue::isClosed() const { return !running; } @@ -266,6 +274,7 @@ unsigned int DataInputQueue::getMaxSize() const { return queue.getMaxSize(); } +// BUGBUG https://github.com/luxonis/depthai-core/issues/762 void DataInputQueue::setMaxDataSize(std::size_t maxSize) { maxDataSize = maxSize; } @@ -288,7 +297,7 @@ void DataInputQueue::send(const std::shared_ptr& rawMsg) { } if(!queue.push(rawMsg)) { - throw std::runtime_error(fmt::format("Underlying queue destructed")); + throw std::runtime_error("Underlying queue destructed"); } } void DataInputQueue::send(const std::shared_ptr& msg) { diff --git a/src/device/Device.cpp b/src/device/Device.cpp index d6187d6fc..eacc86230 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -85,8 +85,6 @@ void Device::closeImpl() { } std::shared_ptr Device::getOutputQueue(const std::string& name) { - checkClosed(); - // Throw if queue not created // all queues for xlink streams are created upfront if(outputQueueMap.count(name) == 0) { @@ -97,8 +95,6 @@ std::shared_ptr Device::getOutputQueue(const std::string& name) } std::shared_ptr Device::getOutputQueue(const std::string& name, unsigned int maxSize, bool blocking) { - checkClosed(); - // Throw if queue not created // all queues for xlink streams are created upfront if(outputQueueMap.count(name) == 0) { @@ -114,8 +110,6 @@ std::shared_ptr Device::getOutputQueue(const std::string& name, } std::vector Device::getOutputQueueNames() const { - checkClosed(); - std::vector names; names.reserve(outputQueueMap.size()); for(const auto& kv : outputQueueMap) { @@ -125,8 +119,6 @@ std::vector Device::getOutputQueueNames() const { } std::shared_ptr Device::getInputQueue(const std::string& name) { - checkClosed(); - // Throw if queue not created // all queues for xlink streams are created upfront if(inputQueueMap.count(name) == 0) { @@ -137,8 +129,6 @@ std::shared_ptr Device::getInputQueue(const std::string& name) { } std::shared_ptr Device::getInputQueue(const std::string& name, unsigned int maxSize, bool blocking) { - checkClosed(); - // Throw if queue not created // all queues for xlink streams are created upfront if(inputQueueMap.count(name) == 0) { @@ -154,8 +144,6 @@ std::shared_ptr Device::getInputQueue(const std::string& name, u } std::vector Device::getInputQueueNames() const { - checkClosed(); - std::vector names; names.reserve(inputQueueMap.size()); for(const auto& kv : inputQueueMap) { @@ -175,8 +163,6 @@ std::vector Device::getInputQueueNames() const { // } std::vector Device::getQueueEvents(const std::vector& queueNames, std::size_t maxNumEvents, std::chrono::microseconds timeout) { - checkClosed(); - // First check if specified queues names are actually opened auto availableQueueNames = getOutputQueueNames(); for(const auto& outputQueue : queueNames) { diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 190f76652..b30edf8b1 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -7,6 +7,7 @@ #include "depthai-bootloader-shared/Bootloader.hpp" #include "depthai-bootloader-shared/XLinkConstants.hpp" #include "depthai-shared/datatype/RawImgFrame.hpp" +#include "depthai-shared/device/CrashDump.hpp" #include "depthai-shared/log/LogConstants.hpp" #include "depthai-shared/log/LogLevel.hpp" #include "depthai-shared/log/LogMessage.hpp" @@ -430,15 +431,14 @@ void DeviceBase::closeImpl() { spdlog::debug("Device closed, {}", duration_cast(steady_clock::now() - t1).count()); } +// This function is thread-unsafe. The idea of "isClosed" is ephemerial and +// is invalidated during the return by value and continues to degrade in +// validity to the caller bool DeviceBase::isClosed() const { std::unique_lock lock(closedMtx); return closed || !watchdogRunning; } -void DeviceBase::checkClosed() const { - if(isClosed()) throw std::invalid_argument("Device already closed or disconnected"); -} - DeviceBase::~DeviceBase() { DeviceBase::close(); } @@ -635,12 +635,18 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionalwrite(std::move(request)); - - // Receive response back - // Send to nanorpc to parse - return rpcStream->read(); + try { + // Send request to device + rpcStream->write(std::move(request)); + + // Receive response back + // Send to nanorpc to parse + return rpcStream->read(); + } catch(const std::exception& e) { + // If any exception is thrown, log it and rethrow + spdlog::debug("RPC error: {}", e.what()); + throw std::system_error(std::make_error_code(std::errc::io_error), "Device already closed or disconnected"); + } }); // prepare watchdog thread, which will keep device alive @@ -797,75 +803,85 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionalrpcClient->call("getMxId").as(); } std::vector DeviceBase::getConnectedCameras() { - checkClosed(); - return pimpl->rpcClient->call("getConnectedCameras").as>(); } std::vector DeviceBase::getConnectedCameraFeatures() { - checkClosed(); - return pimpl->rpcClient->call("getConnectedCameraFeatures").as>(); } std::unordered_map DeviceBase::getCameraSensorNames() { - checkClosed(); - return pimpl->rpcClient->call("getCameraSensorNames").as>(); } +std::string DeviceBase::getConnectedIMU() { + return pimpl->rpcClient->call("getConnectedIMU").as(); +} + +dai::Version DeviceBase::getIMUFirmwareVersion() { + std::string versionStr = pimpl->rpcClient->call("getIMUFirmwareVersion").as(); + try { + dai::Version version = dai::Version(versionStr); + return version; + } catch(const std::exception&) { + dai::Version version = dai::Version(0, 0, 0); + return version; + } +} + +dai::Version DeviceBase::getEmbeddedIMUFirmwareVersion() { + std::string versionStr = pimpl->rpcClient->call("getEmbeddedIMUFirmwareVersion").as(); + try { + dai::Version version = dai::Version(versionStr); + return version; + } catch(const std::exception&) { + dai::Version version = dai::Version(0, 0, 0); + return version; + } +} + +bool DeviceBase::startIMUFirmwareUpdate(bool forceUpdate) { + return pimpl->rpcClient->call("startIMUFirmwareUpdate", forceUpdate).as(); +} + +std::tuple DeviceBase::getIMUFirmwareUpdateStatus() { + return pimpl->rpcClient->call("getIMUFirmwareUpdateStatus").as>(); +} + // Convenience functions for querying current system information MemoryInfo DeviceBase::getDdrMemoryUsage() { - checkClosed(); - return pimpl->rpcClient->call("getDdrUsage").as(); } MemoryInfo DeviceBase::getCmxMemoryUsage() { - checkClosed(); - return pimpl->rpcClient->call("getCmxUsage").as(); } MemoryInfo DeviceBase::getLeonCssHeapUsage() { - checkClosed(); - return pimpl->rpcClient->call("getLeonCssHeapUsage").as(); } MemoryInfo DeviceBase::getLeonMssHeapUsage() { - checkClosed(); - return pimpl->rpcClient->call("getLeonMssHeapUsage").as(); } ChipTemperature DeviceBase::getChipTemperature() { - checkClosed(); - return pimpl->rpcClient->call("getChipTemperature").as(); } CpuUsage DeviceBase::getLeonCssCpuUsage() { - checkClosed(); - return pimpl->rpcClient->call("getLeonCssCpuUsage").as(); } CpuUsage DeviceBase::getLeonMssCpuUsage() { - checkClosed(); - return pimpl->rpcClient->call("getLeonMssCpuUsage").as(); } UsbSpeed DeviceBase::getUsbSpeed() { - checkClosed(); - return pimpl->rpcClient->call("getUsbSpeed").as(); } @@ -874,32 +890,22 @@ tl::optional DeviceBase::getBootloaderVersion() { } bool DeviceBase::isPipelineRunning() { - checkClosed(); - return pimpl->rpcClient->call("isPipelineRunning").as(); } void DeviceBase::setLogLevel(LogLevel level) { - checkClosed(); - pimpl->rpcClient->call("setLogLevel", level); } LogLevel DeviceBase::getLogLevel() { - checkClosed(); - return pimpl->rpcClient->call("getLogLevel").as(); } void DeviceBase::setXLinkChunkSize(int sizeBytes) { - checkClosed(); - pimpl->rpcClient->call("setXLinkChunkSize", sizeBytes); } int DeviceBase::getXLinkChunkSize() { - checkClosed(); - return pimpl->rpcClient->call("getXLinkChunkSize").as(); } @@ -908,8 +914,6 @@ DeviceInfo DeviceBase::getDeviceInfo() const { } std::string DeviceBase::getDeviceName() { - checkClosed(); - std::string deviceName; EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData(); if((deviceName = eeprom.productName).empty()) { @@ -936,38 +940,35 @@ std::string DeviceBase::getDeviceName() { } void DeviceBase::setLogOutputLevel(LogLevel level) { - checkClosed(); - pimpl->setLogLevel(level); } LogLevel DeviceBase::getLogOutputLevel() { - checkClosed(); - return pimpl->getLogLevel(); } bool DeviceBase::setIrLaserDotProjectorBrightness(float mA, int mask) { - checkClosed(); - return pimpl->rpcClient->call("setIrLaserDotProjectorBrightness", mA, mask); } bool DeviceBase::setIrFloodLightBrightness(float mA, int mask) { - checkClosed(); - return pimpl->rpcClient->call("setIrFloodLightBrightness", mA, mask); } std::vector> DeviceBase::getIrDrivers() { - checkClosed(); - return pimpl->rpcClient->call("getIrDrivers"); } -int DeviceBase::addLogCallback(std::function callback) { - checkClosed(); +dai::CrashDump DeviceBase::getCrashDump() { + return pimpl->rpcClient->call("getCrashDump").as(); +} + +bool DeviceBase::hasCrashDump() { + dai::CrashDump crashDump = getCrashDump(); + return !crashDump.crashReports.empty(); +} +int DeviceBase::addLogCallback(std::function callback) { // Lock first std::unique_lock l(logCallbackMapMtx); @@ -982,8 +983,6 @@ int DeviceBase::addLogCallback(std::function callback) { } bool DeviceBase::removeLogCallback(int callbackId) { - checkClosed(); - // Lock first std::unique_lock l(logCallbackMapMtx); @@ -996,8 +995,6 @@ bool DeviceBase::removeLogCallback(int callbackId) { } void DeviceBase::setTimesync(std::chrono::milliseconds period, int numSamples, bool random) { - checkClosed(); - if(period < std::chrono::milliseconds(10)) { throw std::invalid_argument("Period must be greater or equal than 10ms"); } @@ -1015,35 +1012,27 @@ void DeviceBase::setTimesync(bool enable) { } void DeviceBase::setSystemInformationLoggingRate(float rateHz) { - checkClosed(); - pimpl->rpcClient->call("setSystemInformationLoggingRate", rateHz); } float DeviceBase::getSystemInformationLoggingRate() { - checkClosed(); - return pimpl->rpcClient->call("getSystemInformationLoggingrate").as(); } bool DeviceBase::isEepromAvailable() { - checkClosed(); - return pimpl->rpcClient->call("isEepromAvailable").as(); } bool DeviceBase::flashCalibration(CalibrationHandler calibrationDataHandler) { try { flashCalibration2(calibrationDataHandler); - } catch(const EepromError& ex) { + } catch(const EepromError&) { return false; } return true; } void DeviceBase::flashCalibration2(CalibrationHandler calibrationDataHandler) { - checkClosed(); - bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); @@ -1067,14 +1056,12 @@ CalibrationHandler DeviceBase::readCalibration() { dai::EepromData eepromData{}; try { return readCalibration2(); - } catch(const EepromError& ex) { + } catch(const EepromError&) { // ignore - use default } return CalibrationHandler(eepromData); } CalibrationHandler DeviceBase::readCalibration2() { - checkClosed(); - bool success; std::string errorMsg; dai::EepromData eepromData; @@ -1090,8 +1077,6 @@ CalibrationHandler DeviceBase::readCalibrationOrDefault() { } void DeviceBase::flashFactoryCalibration(CalibrationHandler calibrationDataHandler) { - checkClosed(); - bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); @@ -1116,8 +1101,6 @@ void DeviceBase::flashFactoryCalibration(CalibrationHandler calibrationDataHandl } CalibrationHandler DeviceBase::readFactoryCalibration() { - checkClosed(); - bool success; std::string errorMsg; dai::EepromData eepromData; @@ -1131,15 +1114,13 @@ CalibrationHandler DeviceBase::readFactoryCalibrationOrDefault() { dai::EepromData eepromData{}; try { return readFactoryCalibration(); - } catch(const EepromError& ex) { + } catch(const EepromError&) { // ignore - use default } return CalibrationHandler(eepromData); } void DeviceBase::factoryResetCalibration() { - checkClosed(); - bool success; std::string errorMsg; std::tie(success, errorMsg) = pimpl->rpcClient->call("eepromFactoryReset").as>(); @@ -1149,8 +1130,6 @@ void DeviceBase::factoryResetCalibration() { } std::vector DeviceBase::readCalibrationRaw() { - checkClosed(); - bool success; std::string errorMsg; std::vector eepromDataRaw; @@ -1162,8 +1141,6 @@ std::vector DeviceBase::readCalibrationRaw() { } std::vector DeviceBase::readFactoryCalibrationRaw() { - checkClosed(); - bool success; std::string errorMsg; std::vector eepromDataRaw; @@ -1175,8 +1152,6 @@ std::vector DeviceBase::readFactoryCalibrationRaw() { } void DeviceBase::flashEepromClear() { - checkClosed(); - bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); @@ -1195,8 +1170,6 @@ void DeviceBase::flashEepromClear() { } void DeviceBase::flashFactoryEepromClear() { - checkClosed(); - bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); diff --git a/src/device/DeviceBootloader.cpp b/src/device/DeviceBootloader.cpp index 80ee0e112..289060719 100644 --- a/src/device/DeviceBootloader.cpp +++ b/src/device/DeviceBootloader.cpp @@ -21,6 +21,7 @@ #include "utility/spdlog-fmt.hpp" // libraries +#include "XLink/XLink.h" #include "spdlog/fmt/chrono.h" #include "spdlog/spdlog.h" #include "zlib.h" @@ -267,12 +268,28 @@ DeviceBootloader::DeviceBootloader(const DeviceInfo& devInfo, const dai::Path& p init(false, pathToBootloader, tl::nullopt, allowFlashingBootloader); } +DeviceBootloader::DeviceBootloader(std::string nameOrDeviceId, bool allowFlashingBootloader) : deviceInfo(std::move(nameOrDeviceId)) { + init(true, {}, tl::nullopt, allowFlashingBootloader); +} + void DeviceBootloader::init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl::optional type, bool allowBlFlash) { stream = nullptr; allowFlashingBootloader = allowBlFlash; bootloaderType = type.value_or(DEFAULT_TYPE); + // If deviceInfo isn't fully specified (eg ANY_STATE, etc...), but id or name is - try finding it first + if((deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.protocol == X_LINK_ANY_PROTOCOL) && (!deviceInfo.mxid.empty() || !deviceInfo.name.empty())) { + deviceDesc_t foundDesc; + auto ret = XLinkFindFirstSuitableDevice(deviceInfo.getXLinkDeviceDesc(), &foundDesc); + if(ret == X_LINK_SUCCESS) { + deviceInfo = DeviceInfo(foundDesc); + spdlog::debug("Found an actual device by given DeviceInfo: {}", deviceInfo.toString()); + } else { + throw std::runtime_error("Specified device not found"); + } + } + // Init device (if bootloader, handle correctly - issue USB boot command) if(deviceInfo.state == X_LINK_UNBOOTED) { // Unbooted device found, boot to BOOTLOADER and connect with XLinkConnection constructor @@ -542,14 +559,14 @@ void DeviceBootloader::close() { spdlog::debug("DeviceBootloader closed, {}", duration_cast(steady_clock::now() - t1).count()); } +// This function is thread-unsafe. The idea of "isClosed" is ephemerial and +// is invalid even within this function between the evaluation of the logical OR. +// The calculated boolean and then then return by value continue to degrade in +// validity to the caller bool DeviceBootloader::isClosed() const { return closed || !watchdogRunning; } -void DeviceBootloader::checkClosed() const { - if(isClosed()) throw std::invalid_argument("DeviceBootloader already closed or disconnected"); -} - DeviceBootloader::~DeviceBootloader() { close(); } @@ -701,9 +718,10 @@ std::tuple DeviceBootloader::flashDepthaiApplicationPackage(s std::vector package, Memory memory) { // Bug in NETWORK bootloader in version 0.0.12 < 0.0.14 - flashing can cause a soft brick - auto version = getVersion(); - if(bootloaderType == Type::NETWORK && version < Version(0, 0, 14)) { - throw std::invalid_argument("Network bootloader requires version 0.0.14 or higher to flash applications. Current version: " + version.toString()); + auto bootloaderVersion = getVersion(); + if(bootloaderType == Type::NETWORK && bootloaderVersion < Version(0, 0, 14)) { + throw std::invalid_argument("Network bootloader requires version 0.0.14 or higher to flash applications. Current version: " + + bootloaderVersion.toString()); } std::tuple ret; @@ -1085,8 +1103,8 @@ std::tuple DeviceBootloader::flashCustom( std::vector optFileData; if(!filename.empty()) { // Read file into memory first - std::ifstream stream(filename, std::ios::in | std::ios::binary); - optFileData = std::vector(std::istreambuf_iterator(stream), {}); + std::ifstream optFile(filename, std::ios::in | std::ios::binary); + optFileData = std::vector(std::istreambuf_iterator(optFile), {}); data = optFileData.data(); size = optFileData.size(); } @@ -1108,17 +1126,17 @@ std::tuple DeviceBootloader::flashCustom( result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4 result.errorMsg[0] = 0; do { - std::vector data; - if(!receiveResponseData(data)) return {false, "Couldn't receive bootloader response"}; + std::vector responseData; + if(!receiveResponseData(responseData)) return {false, "Couldn't receive bootloader response"}; Response::FlashStatusUpdate update; - if(parseResponse(data, update)) { + if(parseResponse(responseData, update)) { // if progress callback is set if(progressCb != nullptr) { progressCb(update.progress); } // if flash complete response arrived, break from while loop - } else if(parseResponse(data, result)) { + } else if(parseResponse(responseData, result)) { break; } else { // Unknown response, shouldn't happen diff --git a/src/pipeline/Node.cpp b/src/pipeline/Node.cpp index d72ef4622..28aaebb23 100644 --- a/src/pipeline/Node.cpp +++ b/src/pipeline/Node.cpp @@ -91,8 +91,8 @@ void Node::Output::unlink(const Input& in) { parent.getParentPipeline().unlink(*this, in); } -void Node::Input::setBlocking(bool blocking) { - this->blocking = blocking; +void Node::Input::setBlocking(bool newBlocking) { + blocking = newBlocking; } bool Node::Input::getBlocking() const { @@ -103,7 +103,7 @@ bool Node::Input::getBlocking() const { } void Node::Input::setQueueSize(int size) { - this->queueSize = size; + queueSize = size; } int Node::Input::getQueueSize() const { @@ -113,16 +113,16 @@ int Node::Input::getQueueSize() const { return defaultQueueSize; } -void Node::Input::setWaitForMessage(bool waitForMessage) { - this->waitForMessage = waitForMessage; +void Node::Input::setWaitForMessage(bool newWaitForMessage) { + waitForMessage = newWaitForMessage; } bool Node::Input::getWaitForMessage() const { return waitForMessage.value_or(defaultWaitForMessage); } -void Node::Input::setReusePreviousMessage(bool waitForMessage) { - this->waitForMessage = !waitForMessage; +void Node::Input::setReusePreviousMessage(bool reusePreviousMessage) { + waitForMessage = !reusePreviousMessage; } bool Node::Input::getReusePreviousMessage() const { diff --git a/src/pipeline/Pipeline.cpp b/src/pipeline/Pipeline.cpp index 406455905..8a8e3e18b 100644 --- a/src/pipeline/Pipeline.cpp +++ b/src/pipeline/Pipeline.cpp @@ -43,8 +43,8 @@ Pipeline Pipeline::clone() const { return clone; } -Pipeline::Pipeline(const std::shared_ptr& pimpl) { - this->pimpl = pimpl; +Pipeline::Pipeline(const std::shared_ptr& newPimpl) { + pimpl = newPimpl; } GlobalProperties Pipeline::getGlobalProperties() const { @@ -304,8 +304,16 @@ void PipelineImpl::setXLinkChunkSize(int sizeBytes) { globalProperties.xlinkChunkSize = sizeBytes; } -void PipelineImpl::setBoardConfig(BoardConfig board) { - this->board = board; +void PipelineImpl::setSippBufferSize(int sizeBytes) { + globalProperties.sippBufferSize = sizeBytes; +} + +void PipelineImpl::setSippDmaBufferSize(int sizeBytes) { + globalProperties.sippDmaBufferSize = sizeBytes; +} + +void PipelineImpl::setBoardConfig(BoardConfig boardCfg) { + board = boardCfg; } BoardConfig PipelineImpl::getBoardConfig() const { diff --git a/src/pipeline/datatype/StereoDepthConfig.cpp b/src/pipeline/datatype/StereoDepthConfig.cpp index 36c962711..d7715b72a 100644 --- a/src/pipeline/datatype/StereoDepthConfig.cpp +++ b/src/pipeline/datatype/StereoDepthConfig.cpp @@ -81,6 +81,11 @@ StereoDepthConfig& StereoDepthConfig::setDisparityShift(int disparityShift) { return *this; } +StereoDepthConfig& StereoDepthConfig::setNumInvalidateEdgePixels(int32_t numInvalidateEdgePixels) { + cfg.algorithmControl.numInvalidateEdgePixels = numInvalidateEdgePixels; + return *this; +} + dai::StereoDepthConfig::AlgorithmControl::DepthUnit StereoDepthConfig::getDepthUnit() { return cfg.algorithmControl.depthUnit; } diff --git a/src/pipeline/node/Camera.cpp b/src/pipeline/node/Camera.cpp index 09b76bab6..06edcb518 100644 --- a/src/pipeline/node/Camera.cpp +++ b/src/pipeline/node/Camera.cpp @@ -130,6 +130,10 @@ void Camera::setFps(float fps) { properties.fps = fps; } +void Camera::setIsp3aFps(int isp3aFps) { + properties.isp3aFps = isp3aFps; +} + float Camera::getFps() const { // if AUTO if(properties.fps == CameraProperties::AUTO || properties.fps == 0) { diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 2306fa5f1..8f8527810 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -50,9 +50,9 @@ std::string ColorCamera::getCamera() const { } // Set which color camera to use -void ColorCamera::setCamId(int64_t id) { +void ColorCamera::setCamId(int64_t camId) { // cast to board socket - switch(id) { + switch(camId) { case 0: properties.boardSocket = CameraBoardSocket::RGB; break; @@ -66,7 +66,7 @@ void ColorCamera::setCamId(int64_t id) { properties.boardSocket = CameraBoardSocket::CAM_D; break; default: - throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", id)); + throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", camId)); break; } } @@ -177,6 +177,10 @@ void ColorCamera::setFps(float fps) { properties.fps = fps; } +void ColorCamera::setIsp3aFps(int isp3aFps) { + properties.isp3aFps = isp3aFps; +} + void ColorCamera::setFrameEventFilter(const std::vector& events) { properties.eventFilter = events; } @@ -486,12 +490,12 @@ bool ColorCamera::getPreviewKeepAspectRatio() { return properties.previewKeepAspectRatio; } -void ColorCamera::setNumFramesPool(int raw, int isp, int preview, int video, int still) { - properties.numFramesPoolRaw = raw; - properties.numFramesPoolIsp = isp; - properties.numFramesPoolPreview = preview; - properties.numFramesPoolVideo = video; - properties.numFramesPoolStill = still; +void ColorCamera::setNumFramesPool(int numRaw, int numIsp, int numPreview, int numVideo, int numStill) { + properties.numFramesPoolRaw = numRaw; + properties.numFramesPoolIsp = numIsp; + properties.numFramesPoolPreview = numPreview; + properties.numFramesPoolVideo = numVideo; + properties.numFramesPoolStill = numStill; } void ColorCamera::setPreviewNumFramesPool(int num) { diff --git a/src/pipeline/node/MonoCamera.cpp b/src/pipeline/node/MonoCamera.cpp index 6ff9c8806..ea979af0a 100644 --- a/src/pipeline/node/MonoCamera.cpp +++ b/src/pipeline/node/MonoCamera.cpp @@ -42,9 +42,9 @@ std::string MonoCamera::getCamera() const { } // Set which color camera to use -void MonoCamera::setCamId(int64_t id) { +void MonoCamera::setCamId(int64_t camId) { // cast to board socket - switch(id) { + switch(camId) { case 0: properties.boardSocket = CameraBoardSocket::RGB; break; @@ -58,7 +58,7 @@ void MonoCamera::setCamId(int64_t id) { properties.boardSocket = CameraBoardSocket::CAM_D; break; default: - throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", id)); + throw std::invalid_argument(fmt::format("CamId value: {} is invalid.", camId)); break; } } @@ -99,6 +99,10 @@ void MonoCamera::setFps(float fps) { properties.fps = fps; } +void MonoCamera::setIsp3aFps(int isp3aFps) { + properties.isp3aFps = isp3aFps; +} + float MonoCamera::getFps() const { // if AUTO if(properties.fps == -1 || properties.fps == 0) { diff --git a/src/pipeline/node/NeuralNetwork.cpp b/src/pipeline/node/NeuralNetwork.cpp index acfd6d695..aa4f0a83f 100644 --- a/src/pipeline/node/NeuralNetwork.cpp +++ b/src/pipeline/node/NeuralNetwork.cpp @@ -32,7 +32,7 @@ void NeuralNetwork::setBlob(const dai::Path& path) { } void NeuralNetwork::setBlob(OpenVINO::Blob blob) { - this->networkOpenvinoVersion = blob.version; + networkOpenvinoVersion = blob.version; auto asset = assetManager.set("__blob", std::move(blob.data)); properties.blobUri = asset->getRelativeUri(); properties.blobSize = static_cast(asset->data.size()); diff --git a/src/pipeline/node/ObjectTracker.cpp b/src/pipeline/node/ObjectTracker.cpp index 90dfb5a1b..5b7d6fd11 100644 --- a/src/pipeline/node/ObjectTracker.cpp +++ b/src/pipeline/node/ObjectTracker.cpp @@ -32,6 +32,9 @@ void ObjectTracker::setTrackerType(TrackerType type) { void ObjectTracker::setTrackerIdAssignmentPolicy(TrackerIdAssignmentPolicy type) { properties.trackerIdAssignmentPolicy = type; } +void ObjectTracker::setTrackingPerClass(bool trackingPerClass) { + properties.trackingPerClass = trackingPerClass; +} } // namespace node } // namespace dai diff --git a/src/pipeline/node/SPIIn.cpp b/src/pipeline/node/SPIIn.cpp index 06c1d863d..5c1795a73 100644 --- a/src/pipeline/node/SPIIn.cpp +++ b/src/pipeline/node/SPIIn.cpp @@ -14,8 +14,8 @@ void SPIIn::setStreamName(const std::string& name) { properties.streamName = name; } -void SPIIn::setBusId(int id) { - properties.busId = id; +void SPIIn::setBusId(int busId) { + properties.busId = busId; } void SPIIn::setMaxDataSize(std::uint32_t maxDataSize) { diff --git a/src/pipeline/node/SpatialDetectionNetwork.cpp b/src/pipeline/node/SpatialDetectionNetwork.cpp index 0cae9e97f..16cb024c9 100644 --- a/src/pipeline/node/SpatialDetectionNetwork.cpp +++ b/src/pipeline/node/SpatialDetectionNetwork.cpp @@ -35,6 +35,10 @@ void SpatialDetectionNetwork::setSpatialCalculationAlgorithm(dai::SpatialLocatio properties.calculationAlgorithm = calculationAlgorithm; } +void SpatialDetectionNetwork::setSpatialCalculationStepSize(int stepSize) { + properties.stepSize = stepSize; +} + //-------------------------------------------------------------------- // MobileNet //-------------------------------------------------------------------- diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 755982020..91abb5db7 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -186,6 +186,22 @@ void StereoDepth::setFocalLength(float focalLength) { properties.focalLength = focalLength; } +void StereoDepth::setDisparityToDepthUseSpecTranslation(bool specTranslation) { + properties.disparityToDepthUseSpecTranslation = specTranslation; +} + +void StereoDepth::setRectificationUseSpecTranslation(bool specTranslation) { + properties.rectificationUseSpecTranslation = specTranslation; +} + +void StereoDepth::setDepthAlignmentUseSpecTranslation(bool specTranslation) { + properties.depthAlignmentUseSpecTranslation = specTranslation; +} + +void StereoDepth::setAlphaScaling(float alpha) { + properties.alphaScaling = alpha; +} + void StereoDepth::setDefaultProfilePreset(PresetMode mode) { presetMode = mode; switch(presetMode) { diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index d111c1a95..6908c3418 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -113,7 +113,6 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav xlinkGlobalHandler.protocol = X_LINK_USB_VSC; xlinkGlobalHandler.options = javavm; auto status = XLinkInitialize(&xlinkGlobalHandler); - std::string errorMsg; const auto ERROR_MSG_USB_TIP = fmt::format("If running in a container, make sure that the following is set: \"{}\"", "-v /dev/bus/usb:/dev/bus/usb --device-cgroup-rule='c 189:* rmw'"); if(X_LINK_SUCCESS != status) { diff --git a/src/utility/PimplImpl.hpp b/src/utility/PimplImpl.hpp index c2c839d45..9b2204585 100644 --- a/src/utility/PimplImpl.hpp +++ b/src/utility/PimplImpl.hpp @@ -4,21 +4,21 @@ #include namespace dai { - + template Pimpl::Pimpl() : m{ new T{} } { } - + template template Pimpl::Pimpl( Args&& ...args ) : m{ new T{ std::forward(args)... } } { } - + template Pimpl::~Pimpl() { } - + template T* Pimpl::operator->() { return m.get(); } - + template T& Pimpl::operator*() { return *m.get(); } diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index 5e2aa9e65..a025daa87 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -277,47 +277,37 @@ DeviceInfo XLinkConnection::bootBootloader(const DeviceInfo& deviceInfo) { return DeviceInfo(foundDeviceDesc); } -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, std::vector mvcmdBinary, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, std::vector mvcmdBinary, XLinkDeviceState_t expectedState) + : bootWithPath(false), mvcmd(std::move(mvcmdBinary)) { initialize(); - - bootDevice = true; - bootWithPath = false; - this->mvcmd = std::move(mvcmdBinary); initDevice(deviceDesc, expectedState); } -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, dai::Path pathToMvcmd, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, dai::Path mvcmdPath, XLinkDeviceState_t expectedState) : pathToMvcmd(std::move(mvcmdPath)) { initialize(); - if(!pathToMvcmd.empty()) { - std::ifstream f(pathToMvcmd); - if(!f.good()) throw std::runtime_error("Error path doesn't exist. Note: Environment variables in path are not expanded. (E.g. '~', '$PATH')."); + std::ifstream testStream(pathToMvcmd); + if(!testStream.good()) throw std::runtime_error("Error path doesn't exist. Note: Environment variables in path are not expanded. (E.g. '~', '$PATH')."); } - bootDevice = true; - bootWithPath = true; - this->pathToMvcmd = std::move(pathToMvcmd); initDevice(deviceDesc, expectedState); } // Skip boot -XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState) { +XLinkConnection::XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState) : bootDevice(false) { initialize(); - - bootDevice = false; initDevice(deviceDesc, expectedState); } +// This function is thread-unsafe. The `closed` value is only known and valid +// within the context of the lock_guard. The value is immediately invalid and outdated +// when it is returned by value to the caller bool XLinkConnection::isClosed() const { - std::unique_lock lock(closedMtx); + std::lock_guard lock(closedMtx); return closed; } -void XLinkConnection::checkClosed() const { - if(isClosed()) throw std::invalid_argument("XLinkConnection already closed or disconnected"); -} - void XLinkConnection::close() { - std::unique_lock lock(closedMtx); + std::lock_guard lock(closedMtx); if(closed) return; using namespace std::chrono; @@ -325,7 +315,7 @@ void XLinkConnection::close() { constexpr auto BOOTUP_SEARCH = seconds(5); if(deviceLinkId != -1 && rebootOnDestruction) { - auto tmp = deviceLinkId; + auto previousLinkId = deviceLinkId; auto ret = XLinkResetRemoteTimeout(deviceLinkId, duration_cast(RESET_TIMEOUT).count()); if(ret != X_LINK_SUCCESS) { @@ -342,17 +332,17 @@ void XLinkConnection::close() { auto t1 = steady_clock::now(); bool found = false; do { - DeviceInfo tmp; - std::tie(found, tmp) = XLinkConnection::getDeviceByMxId(deviceInfo.getMxId(), X_LINK_ANY_STATE, false); + DeviceInfo rebootingDeviceInfo; + std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByMxId(deviceInfo.getMxId(), X_LINK_ANY_STATE, false); if(found) { - if(tmp.state == X_LINK_UNBOOTED || tmp.state == X_LINK_BOOTLOADER) { + if(rebootingDeviceInfo.state == X_LINK_UNBOOTED || rebootingDeviceInfo.state == X_LINK_BOOTLOADER) { break; } } } while(!found && steady_clock::now() - t1 < BOOTUP_SEARCH); } - spdlog::debug("XLinkResetRemote of linkId: ({})", tmp); + spdlog::debug("XLinkResetRemote of linkId: ({})", previousLinkId); } closed = true; diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index c71936f9b..a1acf6903 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -46,7 +46,7 @@ function(dai_add_test test_name test_src) endif() # Link to core and Catch2 testing framework - target_link_libraries(${test_name} PRIVATE depthai-core Catch2::Catch2 Threads::Threads) + target_link_libraries(${test_name} PRIVATE depthai-core Catch2::Catch2WithMain Threads::Threads) # Add sanitizers for tests as well if(COMMAND add_sanitizers) @@ -68,7 +68,7 @@ function(dai_add_test test_name test_src) add_default_flags(${test_name}_conforming LEAN) # Link to core and Catch2 testing framework - target_link_libraries(${test_name}_conforming PRIVATE depthai-core Catch2::Catch2 Threads::Threads) + target_link_libraries(${test_name}_conforming PRIVATE depthai-core Catch2::Catch2WithMain Threads::Threads) # Set compiler c++ standard target_compile_options(${test_name}_conforming PRIVATE "${CMAKE_CXX${DAT_CXX_STANDARD}_STANDARD_COMPILE_OPTION}") @@ -249,15 +249,20 @@ dai_add_test(xlink_roundtrip_test src/xlink_roundtrip_test.cpp) # # dai_add_test(stability_stress_test src/stability_stress_test.cpp) option(DEPTHAI_STABILITY_STRESS_TEST_DEBUG "Enable visualization for stability stress test" OFF) add_executable(stability_stress_test src/stability_stress_test.cpp) +# Set compiler features (c++14), and disables extensions (g++14) +set_property(TARGET stability_stress_test PROPERTY CXX_STANDARD 14) +set_property(TARGET stability_stress_test PROPERTY CXX_STANDARD_REQUIRED ON) +set_property(TARGET stability_stress_test PROPERTY CXX_EXTENSIONS OFF) + add_default_flags(stability_stress_test LEAN) if(COMMAND target_clangformat_setup) target_clangformat_setup(stability_stress_test "") endif() if(DEPTHAI_STABILITY_TEST_DEBUG) - target_link_libraries(stability_stress_test PRIVATE depthai::opencv opencv_highgui) + target_link_libraries(stability_stress_test PRIVATE depthai::opencv opencv_highgui Threads::Threads) target_compile_definitions(stability_stress_test PRIVATE DEPTHAI_STABILITY_TEST_DEBUG) else() - target_link_libraries(stability_stress_test PRIVATE depthai::core) + target_link_libraries(stability_stress_test PRIVATE depthai::core Threads::Threads) endif() target_compile_definitions(stability_stress_test PRIVATE BLOB_PATH="${tiny_yolo_v4_2021-4_4shave_blob}") # add_test(stability_stress_test stability_stress_test) diff --git a/tests/src/bootloader_config_test.cpp b/tests/src/bootloader_config_test.cpp index 014a82416..2bc7df28d 100644 --- a/tests/src/bootloader_config_test.cpp +++ b/tests/src/bootloader_config_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // std #include diff --git a/tests/src/bootloader_version_test.cpp b/tests/src/bootloader_version_test.cpp index 0e1976241..76c368ec5 100644 --- a/tests/src/bootloader_version_test.cpp +++ b/tests/src/bootloader_version_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // std #include diff --git a/tests/src/device_usbspeed_test.cpp b/tests/src/device_usbspeed_test.cpp index 39555b23d..d5d99b7a5 100644 --- a/tests/src/device_usbspeed_test.cpp +++ b/tests/src/device_usbspeed_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // std #include diff --git a/tests/src/filesystem_test.cpp b/tests/src/filesystem_test.cpp index 3224bbcb2..678bf2c31 100644 --- a/tests/src/filesystem_test.cpp +++ b/tests/src/filesystem_test.cpp @@ -1,5 +1,7 @@ -#define CATCH_CONFIG_MAIN -#include +#include +#include + +using namespace Catch::Matchers; // Include depthai library #include @@ -150,15 +152,14 @@ TEST_CASE("dai::Path with NN blobs") { // attempt to use a non-existing blob at a utf-8 path #if defined(_WIN32) && defined(_MSC_VER) - REQUIRE_THROWS_WITH(nn->setBlobPath(PATH4), Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains("not convertible")); - REQUIRE_THROWS_WITH(nn->setBlobPath(strPath), Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains("not convertible")); - REQUIRE_THROWS_WITH(nn->setBlobPath(daiPath), Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains("not convertible")); + REQUIRE_THROWS_WITH(nn->setBlobPath(PATH4), ContainsSubstring("Cannot load blob") && ContainsSubstring("not convertible")); + REQUIRE_THROWS_WITH(nn->setBlobPath(strPath), ContainsSubstring("Cannot load blob") && ContainsSubstring("not convertible")); + REQUIRE_THROWS_WITH(nn->setBlobPath(daiPath), ContainsSubstring("Cannot load blob") && ContainsSubstring("not convertible")); #else - REQUIRE_THROWS_WITH(nn->setBlobPath(PATH4), Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains(dai::Path(PATH4).string())); - REQUIRE_THROWS_WITH( - nn->setBlobPath(strPath), - Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains(std::string{reinterpret_cast(strPath.c_str())})); - REQUIRE_THROWS_WITH(nn->setBlobPath(daiPath), Catch::Matchers::Contains("Cannot load blob") && Catch::Matchers::Contains(daiPath.string())); + REQUIRE_THROWS_WITH(nn->setBlobPath(PATH4), ContainsSubstring(std::string("Cannot load blob")) && ContainsSubstring(dai::Path(PATH4).string())); + REQUIRE_THROWS_WITH(nn->setBlobPath(strPath), + ContainsSubstring("Cannot load blob") && ContainsSubstring(std::string{reinterpret_cast(strPath.c_str())})); + REQUIRE_THROWS_WITH(nn->setBlobPath(daiPath), ContainsSubstring("Cannot load blob") && ContainsSubstring(daiPath.string())); #endif // use blob at known test path @@ -192,24 +193,24 @@ TEST_CASE("dai::Path with Device") { dai::Pipeline pipeline; auto nn = pipeline.create(); REQUIRE_NOTHROW(nn->setBlobPath(BLOB_PATH)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, PATH5), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, &badfile[0]), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, strBadfile), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, diaBadFile), Catch::Matchers::Contains(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, PATH5), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, &badfile[0]), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, strBadfile), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, diaBadFile), ContainsSubstring(PATH5)); #if defined(_WIN32) && defined(_MSC_VER) const wchar_t wideBadfile[] = LPATH5; const std::wstring wstrBadfile(LPATH5); const dai::Path diaFileFromWide(LPATH5); - REQUIRE_THROWS_WITH(dai::Device(pipeline, LPATH5), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, &wideBadfile[0]), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, wstrBadfile), Catch::Matchers::Contains(PATH5)); - REQUIRE_THROWS_WITH(dai::Device(pipeline, diaFileFromWide), Catch::Matchers::Contains(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, LPATH5), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, &wideBadfile[0]), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, wstrBadfile), ContainsSubstring(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, diaFileFromWide), ContainsSubstring(PATH5)); #endif #if defined(__cpp_lib_filesystem) std::filesystem::path stdBadfile(PATH5); - REQUIRE_THROWS_WITH(dai::Device(pipeline, stdBadfile), Catch::Matchers::Contains(PATH5)); + REQUIRE_THROWS_WITH(dai::Device(pipeline, stdBadfile), ContainsSubstring(PATH5)); #endif dai::Device d(pipeline); @@ -263,38 +264,38 @@ TEST_CASE("dai::Path with DeviceBootloader") { dai::DeviceBootloader bl(deviceInfo, &badfile[0]); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); REQUIRE_THROWS_WITH( [&]() { dai::DeviceBootloader bl(deviceInfo, strBadfile); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); REQUIRE_THROWS_WITH( [&]() { dai::DeviceBootloader bl(deviceInfo, diaBadfile); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); #if defined(_WIN32) && defined(_MSC_VER) REQUIRE_THROWS_WITH( [&]() { dai::DeviceBootloader bl(deviceInfo, &wideBadfile[0]); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); REQUIRE_THROWS_WITH( [&]() { dai::DeviceBootloader bl(deviceInfo, wstrBadfile); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); REQUIRE_THROWS_WITH( [&]() { dai::DeviceBootloader bl(deviceInfo, diaBadWide); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); #endif #if defined(__cpp_lib_filesystem) #if defined(__cpp_lib_char8_t) @@ -307,7 +308,7 @@ TEST_CASE("dai::Path with DeviceBootloader") { dai::DeviceBootloader bl(deviceInfo, stdBadpath); auto currentBlType = bl.getType(); }(), - Catch::Matchers::Contains("doesn't exist")); + ContainsSubstring("doesn't exist")); #endif } else { std::cout << "No devices found" << std::endl; diff --git a/tests/src/logging_test.cpp b/tests/src/logging_test.cpp index 0ac7793c2..b411d6a42 100644 --- a/tests/src/logging_test.cpp +++ b/tests/src/logging_test.cpp @@ -1,7 +1,6 @@ -#define CATCH_CONFIG_MAIN #include -#include +#include #include #include diff --git a/tests/src/neural_network_test.cpp b/tests/src/neural_network_test.cpp index d94976e61..e01ed2e9a 100644 --- a/tests/src/neural_network_test.cpp +++ b/tests/src/neural_network_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // std #include diff --git a/tests/src/openvino_blob_test.cpp b/tests/src/openvino_blob_test.cpp index 1597f0fc4..b20f12bc4 100644 --- a/tests/src/openvino_blob_test.cpp +++ b/tests/src/openvino_blob_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // std #include diff --git a/tests/src/pipeline_test.cpp b/tests/src/pipeline_test.cpp index 66fd1d308..5cc9ae310 100644 --- a/tests/src/pipeline_test.cpp +++ b/tests/src/pipeline_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // Include depthai library #include diff --git a/tests/src/serialization_test.cpp b/tests/src/serialization_test.cpp index 36df33055..fcf3921de 100644 --- a/tests/src/serialization_test.cpp +++ b/tests/src/serialization_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // Include depthai library #include diff --git a/tests/src/unlimited_io_connection_test.cpp b/tests/src/unlimited_io_connection_test.cpp index b7d3b0f4f..47fc8811b 100644 --- a/tests/src/unlimited_io_connection_test.cpp +++ b/tests/src/unlimited_io_connection_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // Include depthai library #include diff --git a/tests/src/xlink_roundtrip_test.cpp b/tests/src/xlink_roundtrip_test.cpp index ae2f4bdf3..ab99e9a00 100644 --- a/tests/src/xlink_roundtrip_test.cpp +++ b/tests/src/xlink_roundtrip_test.cpp @@ -1,5 +1,4 @@ -#define CATCH_CONFIG_MAIN -#include +#include // Include depthai library #include