diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 5692d7351..f76e57fb7 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,27 @@ Changelog for package depthai ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.22.0 (2023-06-15) +----------- +* UVC Node - Capability to create a pipeline that sends data over UVC (or flash it) +* ToF Node - Capability to decode ToF data into a depth map +* New devices: OAK-D-SR (fixes), OAK-D-LR R1, OAK-D SR PoE +* Reorganized CameraBoardSocket naming +* Logging improvements +* Added data throughput profiling, per device and globally +* Added DEPTHAI_DEVICE_NAME_LIST env var to filter devices by name +* Bootloader v0.0.26 - Fix for bootloader crash (USB variant) +* Fix for 4 cameras via ETH +* Device constructor bugfixes (when taking pipeline, or pipeline with config preapplied, etc...) +* XLink - Bugfix for wrongly discovered usb path on Windows +* OV9782 startup stream issue fix +* #779 - Fixes a parsing issue +* #469 - Fixes a stuck case if same stream names are used +* Deprecated RGB/LEFT/RIGHT/... CamerBoardSocket naming. Rely on CAM_[A-H] or setName API +* Add option to clear crash dump +* XLink - Added 255.255.255.255 discovery and increased PoE search time +* Contributors: Alex Bougdan, Szabolcs Gergely, Martin Peterlin + 2.21.2 (2023-04-05) ----------- * UPDATE: Use v2.21.2 due to issues this version carries diff --git a/CMakeLists.txt b/CMakeLists.txt index d1ba1fe6b..de13b019a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -45,7 +45,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.21.2" LANGUAGES CXX C) +project(depthai VERSION "2.22.0" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) @@ -207,6 +207,7 @@ add_library(${TARGET_CORE_NAME} src/pipeline/node/XLinkOut.cpp src/pipeline/node/ColorCamera.cpp src/pipeline/node/Camera.cpp + src/pipeline/node/ToF.cpp src/pipeline/node/MonoCamera.cpp src/pipeline/node/StereoDepth.cpp src/pipeline/node/NeuralNetwork.cpp @@ -225,6 +226,7 @@ add_library(${TARGET_CORE_NAME} src/pipeline/node/SPIIn.cpp src/pipeline/node/FeatureTracker.cpp src/pipeline/node/DetectionParser.cpp + src/pipeline/node/UVC.cpp src/pipeline/datatype/Buffer.cpp src/pipeline/datatype/ImgFrame.cpp src/pipeline/datatype/ImageManipConfig.cpp @@ -244,11 +246,14 @@ add_library(${TARGET_CORE_NAME} src/pipeline/datatype/EdgeDetectorConfig.cpp src/pipeline/datatype/TrackedFeatures.cpp src/pipeline/datatype/FeatureTrackerConfig.cpp + src/pipeline/datatype/ToFConfig.cpp src/utility/Initialization.cpp src/utility/Resources.cpp src/utility/Path.cpp src/utility/Platform.cpp src/utility/Environment.cpp + src/utility/XLinkGlobalProfilingLogger.cpp + src/utility/Logging.cpp src/xlink/XLinkConnection.cpp src/xlink/XLinkStream.cpp src/openvino/OpenVINO.cpp diff --git a/README.md b/README.md index 62564c22e..ecd8a78ca 100644 --- a/README.md +++ b/README.md @@ -177,7 +177,9 @@ The following environment variables can be set to alter default behavior of the | DEPTHAI_CONNECT_TIMEOUT | Specifies timeout in milliseconds for establishing a connection to a given device. | | DEPTHAI_BOOTUP_TIMEOUT | Specifies timeout in milliseconds for waiting the device to boot after sending the binary. | | DEPTHAI_PROTOCOL | Restricts default search to the specified protocol. Options: any, usb, tcpip. | -| DEPTHAI_DEVICE_MXID_LIST | Restricts default search to the specified MXIDs. Accepts comma separated list of MXIDs | +| DEPTHAI_DEVICE_MXID_LIST | Restricts default search to the specified MXIDs. Accepts comma separated list of MXIDs. Lists filter results in an "AND" manner and not "OR" | +| DEPTHAI_DEVICE_ID_LIST | Alias to MXID list. Lists filter results in an "AND" manner and not "OR" | +| DEPTHAI_DEVICE_NAME_LIST | Restricts default search to the specified NAMEs. Accepts comma separated list of NAMEs. Lists filter results in an "AND" manner and not "OR" | | DEPTHAI_DEVICE_BINARY | Overrides device Firmware binary. Mostly for internal debugging purposes. | | DEPTHAI_BOOTLOADER_BINARY_USB | Overrides device USB Bootloader binary. Mostly for internal debugging purposes. | | DEPTHAI_BOOTLOADER_BINARY_ETH | Overrides device Network Bootloader binary. Mostly for internal debugging purposes. | diff --git a/cmake/Depthai/DepthaiBootloaderConfig.cmake b/cmake/Depthai/DepthaiBootloaderConfig.cmake index 9302acfdf..b8c9e058d 100644 --- a/cmake/Depthai/DepthaiBootloaderConfig.cmake +++ b/cmake/Depthai/DepthaiBootloaderConfig.cmake @@ -3,5 +3,5 @@ set(DEPTHAI_BOOTLOADER_MATURITY "release") # set(DEPTHAI_BOOTLOADER_MATURITY "snapshot") # "version if applicable" -set(DEPTHAI_BOOTLOADER_VERSION "0.0.24") -# set(DEPTHAI_BOOTLOADER_VERSION "0.0.23+9704fa354a72599286e0be08663cee084266fda6") +set(DEPTHAI_BOOTLOADER_VERSION "0.0.26") +# set(DEPTHAI_BOOTLOADER_VERSION "0.0.24+57c26493754e2f00e57f6594b0b1a317f762d5f2") diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 4244d4727..86f39611d 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 "3575b77f20e796b4e79953bf3d2ba22f0416ee8b") +set(DEPTHAI_DEVICE_SIDE_COMMIT "f033fd9c7eb0b3578d12f90302e87759c78cfb36") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/cmake/Hunter/config.cmake b/cmake/Hunter/config.cmake index dc189ea09..5142bc426 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/b7c3aca2ba8b9d598be886a8076a875b50f5184f.tar.gz" - SHA1 "6c19757c6fe6871a9f40688871edbfc6f1e939ee" + URL "https://github.com/luxonis/XLink/archive/457b23fb33e1146610e1a4e52defa7565046977a.tar.gz" + SHA1 "006a2bd391498aea7895e988b787a420e7f51fa9" ) hunter_config( diff --git a/examples/AprilTag/apriltag.cpp b/examples/AprilTag/apriltag.cpp index b28f9c133..130acf81b 100644 --- a/examples/AprilTag/apriltag.cpp +++ b/examples/AprilTag/apriltag.cpp @@ -23,7 +23,7 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); aprilTag->initialConfig.setFamily(dai::AprilTagConfig::Family::TAG_36H11); diff --git a/examples/AprilTag/apriltag_rgb.cpp b/examples/AprilTag/apriltag_rgb.cpp index 9bdef1527..b9c419c6f 100644 --- a/examples/AprilTag/apriltag_rgb.cpp +++ b/examples/AprilTag/apriltag_rgb.cpp @@ -24,7 +24,7 @@ int main() { // Properties camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); manip->initialConfig.setResize(480, 270); manip->initialConfig.setFrameType(dai::ImgFrame::Type::GRAY8); diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 97b31f65c..41272b289 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -241,6 +241,7 @@ dai_add_example(device_queue_event host_side/device_queue_event.cpp ON) dai_add_example(opencv_support host_side/opencv_support.cpp ON) dai_add_example(queue_add_callback host_side/queue_add_callback.cpp ON) dai_add_example(device_information host_side/device_information.cpp OFF) +dai_add_example(device_logging host_side/device_logging.cpp OFF) # ImageManip dai_add_example(image_manip ImageManip/image_manip_example.cpp ON) diff --git a/examples/ColorCamera/rgb_isp_scale.cpp b/examples/ColorCamera/rgb_isp_scale.cpp index b0bc78343..78421d06e 100644 --- a/examples/ColorCamera/rgb_isp_scale.cpp +++ b/examples/ColorCamera/rgb_isp_scale.cpp @@ -14,7 +14,7 @@ int main() { xoutVideo->setStreamName("video"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_4_K); camRgb->setIspScale(1, 2); camRgb->setVideoSize(1920, 1080); diff --git a/examples/ColorCamera/rgb_preview.cpp b/examples/ColorCamera/rgb_preview.cpp index e24323a72..1151195d4 100644 --- a/examples/ColorCamera/rgb_preview.cpp +++ b/examples/ColorCamera/rgb_preview.cpp @@ -16,7 +16,7 @@ int main() { // Properties camRgb->setPreviewSize(300, 300); - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setInterleaved(false); camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::RGB); diff --git a/examples/ColorCamera/rgb_video.cpp b/examples/ColorCamera/rgb_video.cpp index 0c660b7eb..fd0b50d1d 100644 --- a/examples/ColorCamera/rgb_video.cpp +++ b/examples/ColorCamera/rgb_video.cpp @@ -14,7 +14,7 @@ int main() { xoutVideo->setStreamName("video"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setVideoSize(1920, 1080); diff --git a/examples/EdgeDetector/edge_detector.cpp b/examples/EdgeDetector/edge_detector.cpp index eff7b1afd..9ffd01e47 100644 --- a/examples/EdgeDetector/edge_detector.cpp +++ b/examples/EdgeDetector/edge_detector.cpp @@ -34,13 +34,13 @@ int main() { xinEdgeCfg->setStreamName(edgeCfgStr); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); edgeDetectorRgb->setMaxOutputFrameSize(camRgb->getVideoWidth() * camRgb->getVideoHeight()); diff --git a/examples/FeatureTracker/feature_detector.cpp b/examples/FeatureTracker/feature_detector.cpp index 966535c73..9755dea6c 100644 --- a/examples/FeatureTracker/feature_detector.cpp +++ b/examples/FeatureTracker/feature_detector.cpp @@ -40,9 +40,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // Disable optical flow featureTrackerLeft->initialConfig.setMotionEstimator(false); diff --git a/examples/FeatureTracker/feature_tracker.cpp b/examples/FeatureTracker/feature_tracker.cpp index 422128801..e7b688158 100644 --- a/examples/FeatureTracker/feature_tracker.cpp +++ b/examples/FeatureTracker/feature_tracker.cpp @@ -106,9 +106,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // Linking monoLeft->out.link(featureTrackerLeft->inputImage); diff --git a/examples/ImageManip/image_manip_rotate.cpp b/examples/ImageManip/image_manip_rotate.cpp index dd9811746..aa0c0bbff 100644 --- a/examples/ImageManip/image_manip_rotate.cpp +++ b/examples/ImageManip/image_manip_rotate.cpp @@ -29,7 +29,7 @@ int main() { // Rotate mono frames auto monoLeft = pipeline.create(); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); auto manipLeft = pipeline.create(); dai::RotatedRect rr = {{monoLeft->getResolutionWidth() / 2.0f, monoLeft->getResolutionHeight() / 2.0f}, // center diff --git a/examples/MobileNet/mono_mobilenet.cpp b/examples/MobileNet/mono_mobilenet.cpp index 2ba61f440..407b6b4b9 100644 --- a/examples/MobileNet/mono_mobilenet.cpp +++ b/examples/MobileNet/mono_mobilenet.cpp @@ -38,7 +38,7 @@ int main(int argc, char** argv) { nnOut->setStreamName("nn"); // Properties - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); // Convert the grayscale frame into the nn-acceptable form diff --git a/examples/MonoCamera/mono_camera_control.cpp b/examples/MonoCamera/mono_camera_control.cpp index 75c69164b..8c6e4377f 100644 --- a/examples/MonoCamera/mono_camera_control.cpp +++ b/examples/MonoCamera/mono_camera_control.cpp @@ -50,8 +50,8 @@ int main() { dai::Point2f bottomRight(0.8f, 0.8f); // Properties - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoRight->setCamera("right"); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); manipRight->initialConfig.setCropRect(topLeft.x, topLeft.y, bottomRight.x, bottomRight.y); diff --git a/examples/MonoCamera/mono_full_resolution_saver.cpp b/examples/MonoCamera/mono_full_resolution_saver.cpp index 9330140aa..a1c4f901b 100644 --- a/examples/MonoCamera/mono_full_resolution_saver.cpp +++ b/examples/MonoCamera/mono_full_resolution_saver.cpp @@ -17,7 +17,7 @@ int main() { xoutRight->setStreamName("right"); // Properties - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); // Linking diff --git a/examples/MonoCamera/mono_preview.cpp b/examples/MonoCamera/mono_preview.cpp index b4c83dda0..55661466b 100644 --- a/examples/MonoCamera/mono_preview.cpp +++ b/examples/MonoCamera/mono_preview.cpp @@ -17,9 +17,9 @@ int main() { xoutRight->setStreamName("right"); // Properties - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); // Linking diff --git a/examples/NeuralNetwork/concat_multi_input.cpp b/examples/NeuralNetwork/concat_multi_input.cpp index 1dc57d6d3..bfa33b8d8 100644 --- a/examples/NeuralNetwork/concat_multi_input.cpp +++ b/examples/NeuralNetwork/concat_multi_input.cpp @@ -31,7 +31,7 @@ int main(int argc, char** argv) { camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); auto right = pipeline.create(); - right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + right->setCamera("right"); right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); auto manipRight = pipeline.create(); @@ -40,7 +40,7 @@ int main(int argc, char** argv) { right->out.link(manipRight->inputImage); auto left = pipeline.create(); - left->setBoardSocket(dai::CameraBoardSocket::LEFT); + left->setCamera("left"); left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); auto manipLeft = pipeline.create(); diff --git a/examples/ObjectTracker/spatial_object_tracker.cpp b/examples/ObjectTracker/spatial_object_tracker.cpp index fec128ad8..7912cb669 100644 --- a/examples/ObjectTracker/spatial_object_tracker.cpp +++ b/examples/ObjectTracker/spatial_object_tracker.cpp @@ -48,14 +48,14 @@ int main(int argc, char** argv) { camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // setting node configs stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // Align depth map to the perspective of RGB camera, on which inference is done - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight()); spatialDetectionNetwork->setBlobPath(nnPath); diff --git a/examples/Script/script_change_pipeline_flow.cpp b/examples/Script/script_change_pipeline_flow.cpp index 5993d7252..2928beef9 100644 --- a/examples/Script/script_change_pipeline_flow.cpp +++ b/examples/Script/script_change_pipeline_flow.cpp @@ -7,7 +7,7 @@ int main() { dai::Pipeline pipeline; auto cam = pipeline.create(); - cam->setBoardSocket(dai::CameraBoardSocket::RGB); + cam->setBoardSocket(dai::CameraBoardSocket::CAM_A); cam->setInterleaved(false); cam->setIspScale(2, 3); cam->setVideoSize(720, 720); diff --git a/examples/SpatialDetection/spatial_calculator_multi_roi.cpp b/examples/SpatialDetection/spatial_calculator_multi_roi.cpp index e425905fa..c24e81982 100644 --- a/examples/SpatialDetection/spatial_calculator_multi_roi.cpp +++ b/examples/SpatialDetection/spatial_calculator_multi_roi.cpp @@ -31,9 +31,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); stereo->setLeftRightCheck(true); diff --git a/examples/SpatialDetection/spatial_location_calculator.cpp b/examples/SpatialDetection/spatial_location_calculator.cpp index 5e7cd9c43..192054682 100644 --- a/examples/SpatialDetection/spatial_location_calculator.cpp +++ b/examples/SpatialDetection/spatial_location_calculator.cpp @@ -31,9 +31,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); bool lrcheck = false; bool subpixel = false; diff --git a/examples/SpatialDetection/spatial_mobilenet.cpp b/examples/SpatialDetection/spatial_mobilenet.cpp index 53663bdef..1b93ee80a 100644 --- a/examples/SpatialDetection/spatial_mobilenet.cpp +++ b/examples/SpatialDetection/spatial_mobilenet.cpp @@ -48,14 +48,14 @@ int main(int argc, char** argv) { camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // Setting node configs stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // Align depth map to the perspective of RGB camera, on which inference is done - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight()); spatialDetectionNetwork->setBlobPath(nnPath); diff --git a/examples/SpatialDetection/spatial_mobilenet_mono.cpp b/examples/SpatialDetection/spatial_mobilenet_mono.cpp index 3fef89100..ab50bfaaa 100644 --- a/examples/SpatialDetection/spatial_mobilenet_mono.cpp +++ b/examples/SpatialDetection/spatial_mobilenet_mono.cpp @@ -47,9 +47,9 @@ int main(int argc, char** argv) { imageManip->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // StereoDepth stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); diff --git a/examples/SpatialDetection/spatial_tiny_yolo.cpp b/examples/SpatialDetection/spatial_tiny_yolo.cpp index 6bbe27cf9..9820dcbba 100644 --- a/examples/SpatialDetection/spatial_tiny_yolo.cpp +++ b/examples/SpatialDetection/spatial_tiny_yolo.cpp @@ -58,14 +58,14 @@ int main(int argc, char** argv) { camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // setting node configs stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // Align depth map to the perspective of RGB camera, on which inference is done - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight()); spatialDetectionNetwork->setBlobPath(nnPath); diff --git a/examples/StereoDepth/depth_crop_control.cpp b/examples/StereoDepth/depth_crop_control.cpp index 2a2467e16..dd1459303 100644 --- a/examples/StereoDepth/depth_crop_control.cpp +++ b/examples/StereoDepth/depth_crop_control.cpp @@ -31,8 +31,8 @@ int main() { dai::Point2f bottomRight(0.8f, 0.8f); // Properties - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoRight->setCamera("right"); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); diff --git a/examples/StereoDepth/depth_post_processing.cpp b/examples/StereoDepth/depth_post_processing.cpp index 63c71d3d4..ca602af7a 100644 --- a/examples/StereoDepth/depth_post_processing.cpp +++ b/examples/StereoDepth/depth_post_processing.cpp @@ -24,9 +24,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way) depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); diff --git a/examples/StereoDepth/depth_preview.cpp b/examples/StereoDepth/depth_preview.cpp index 8530d3a60..f8fd77d29 100644 --- a/examples/StereoDepth/depth_preview.cpp +++ b/examples/StereoDepth/depth_preview.cpp @@ -24,9 +24,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way) depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); diff --git a/examples/StereoDepth/rgb_depth_aligned.cpp b/examples/StereoDepth/rgb_depth_aligned.cpp index 174edc8c7..19a1fe2a4 100644 --- a/examples/StereoDepth/rgb_depth_aligned.cpp +++ b/examples/StereoDepth/rgb_depth_aligned.cpp @@ -44,7 +44,7 @@ int main() { queueNames.push_back("depth"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setFps(fps); if(downscaleColor) camRgb->setIspScale(2, 3); @@ -52,7 +52,7 @@ int main() { // This value was used during calibration try { auto calibData = device.readCalibration2(); - auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::RGB); + auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::CAM_A); if(lensPosition) { camRgb->initialControl.setManualFocus(lensPosition); } @@ -62,16 +62,16 @@ int main() { } left->setResolution(monoRes); - left->setBoardSocket(dai::CameraBoardSocket::LEFT); + left->setCamera("left"); left->setFps(fps); right->setResolution(monoRes); - right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + right->setCamera("right"); right->setFps(fps); stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // LR-check is required for depth alignment stereo->setLeftRightCheck(true); - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); // Linking camRgb->isp.link(rgbOut->input); diff --git a/examples/StereoDepth/rgb_depth_confidence_aligned.cpp b/examples/StereoDepth/rgb_depth_confidence_aligned.cpp index 4a19a5cc7..94a5e73da 100644 --- a/examples/StereoDepth/rgb_depth_confidence_aligned.cpp +++ b/examples/StereoDepth/rgb_depth_confidence_aligned.cpp @@ -51,7 +51,7 @@ int main() { queueNames.push_back("conf"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setFps(fps); if(downscaleColor) camRgb->setIspScale(2, 3); @@ -59,7 +59,7 @@ int main() { // This value was used during calibration try { auto calibData = device.readCalibration2(); - auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::RGB); + auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::CAM_A); if(lensPosition) { camRgb->initialControl.setManualFocus(lensPosition); } @@ -69,16 +69,16 @@ int main() { } left->setResolution(monoRes); - left->setBoardSocket(dai::CameraBoardSocket::LEFT); + left->setCamera("left"); left->setFps(fps); right->setResolution(monoRes); - right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + right->setCamera("right"); right->setFps(fps); stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // LR-check is required for depth alignment stereo->setLeftRightCheck(true); - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); // Linking camRgb->isp.link(rgbOut->input); diff --git a/examples/StereoDepth/stereo_depth_video.cpp b/examples/StereoDepth/stereo_depth_video.cpp index e30e76051..7821db3e7 100644 --- a/examples/StereoDepth/stereo_depth_video.cpp +++ b/examples/StereoDepth/stereo_depth_video.cpp @@ -41,9 +41,9 @@ int main() { // Properties monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); if(withDepth) { // StereoDepth diff --git a/examples/VideoEncoder/disparity_encoding.cpp b/examples/VideoEncoder/disparity_encoding.cpp index efe670d2a..e826ac8ec 100644 --- a/examples/VideoEncoder/disparity_encoding.cpp +++ b/examples/VideoEncoder/disparity_encoding.cpp @@ -19,11 +19,11 @@ int main() { // Define sources and outputs auto monoLeft = pipeline.create(); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); auto monoRight = pipeline.create(); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); auto stereo = pipeline.create(); stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); diff --git a/examples/VideoEncoder/encoding_max_limit.cpp b/examples/VideoEncoder/encoding_max_limit.cpp index d93c1a7bb..e3c9111db 100644 --- a/examples/VideoEncoder/encoding_max_limit.cpp +++ b/examples/VideoEncoder/encoding_max_limit.cpp @@ -35,10 +35,10 @@ int main() { ve3Out->setStreamName("ve3Out"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_4_K); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoLeft->setCamera("left"); + monoRight->setCamera("right"); // Setting to 26fps will trigger error ve1->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H264_MAIN); diff --git a/examples/VideoEncoder/rgb_encoding.cpp b/examples/VideoEncoder/rgb_encoding.cpp index 7fdb7baec..d2096d37a 100644 --- a/examples/VideoEncoder/rgb_encoding.cpp +++ b/examples/VideoEncoder/rgb_encoding.cpp @@ -25,7 +25,7 @@ int main(int argc, char** argv) { xout->setStreamName("h265"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_4_K); videoEnc->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H265_MAIN); diff --git a/examples/VideoEncoder/rgb_full_resolution_saver.cpp b/examples/VideoEncoder/rgb_full_resolution_saver.cpp index 25f2e32d4..a6579eab5 100644 --- a/examples/VideoEncoder/rgb_full_resolution_saver.cpp +++ b/examples/VideoEncoder/rgb_full_resolution_saver.cpp @@ -21,7 +21,7 @@ int main() { xoutRgb->setStreamName("rgb"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_4_K); videoEnc->setDefaultProfilePreset(camRgb->getFps(), dai::VideoEncoderProperties::Profile::MJPEG); diff --git a/examples/VideoEncoder/rgb_mono_encoding.cpp b/examples/VideoEncoder/rgb_mono_encoding.cpp index 21c3fe548..2375e8f63 100644 --- a/examples/VideoEncoder/rgb_mono_encoding.cpp +++ b/examples/VideoEncoder/rgb_mono_encoding.cpp @@ -34,9 +34,9 @@ int main() { ve3Out->setStreamName("ve3Out"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); + monoLeft->setCamera("left"); + monoRight->setCamera("right"); // Create encoders, one for each camera, consuming the frames and encoding them using H.264 / H.265 encoding ve1->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H264_MAIN); ve2->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H265_MAIN); diff --git a/examples/calibration/calibration_load.cpp b/examples/calibration/calibration_load.cpp index 1c9127550..8e14d5b57 100644 --- a/examples/calibration/calibration_load.cpp +++ b/examples/calibration/calibration_load.cpp @@ -27,10 +27,10 @@ int main(int argc, char** argv) { // MonoCamera monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); // monoLeft->setFps(5.0); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); // monoRight->setFps(5.0); // Linking diff --git a/examples/calibration/calibration_reader.cpp b/examples/calibration/calibration_reader.cpp index 9f710c1de..e17dd90b1 100644 --- a/examples/calibration/calibration_reader.cpp +++ b/examples/calibration/calibration_reader.cpp @@ -31,7 +31,7 @@ int main(int argc, char** argv) { int width, height; cout << "Intrinsics from defaultIntrinsics function:" << endl; - std::tie(intrinsics, width, height) = calibData.getDefaultIntrinsics(dai::CameraBoardSocket::RIGHT); + std::tie(intrinsics, width, height) = calibData.getDefaultIntrinsics(dai::CameraBoardSocket::CAM_C); printMatrix(intrinsics); cout << "Width: " << width << endl; @@ -39,45 +39,45 @@ int main(int argc, char** argv) { cout << "Stereo baseline distance: " << calibData.getBaselineDistance() << " cm" << endl; - cout << "Mono FOV from camera specs: " << calibData.getFov(dai::CameraBoardSocket::LEFT) - << ", calculated FOV: " << calibData.getFov(dai::CameraBoardSocket::LEFT, false) << endl; + cout << "Mono FOV from camera specs: " << calibData.getFov(dai::CameraBoardSocket::CAM_B) + << ", calculated FOV: " << calibData.getFov(dai::CameraBoardSocket::CAM_B, false) << endl; cout << "Intrinsics from getCameraIntrinsics function full resolution:" << endl; - intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::RIGHT); + intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C); printMatrix(intrinsics); cout << "Intrinsics from getCameraIntrinsics function 1280 x 720:" << endl; - intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::RIGHT, 1280, 720); + intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 1280, 720); printMatrix(intrinsics); cout << "Intrinsics from getCameraIntrinsics function 720 x 450:" << endl; - intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::RIGHT, 720); + intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 720); printMatrix(intrinsics); cout << "Intrinsics from getCameraIntrinsics function 600 x 1280:" << endl; - intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::RIGHT, 600, 1280); + intrinsics = calibData.getCameraIntrinsics(dai::CameraBoardSocket::CAM_C, 600, 1280); printMatrix(intrinsics); std::vector> extrinsics; cout << "Extrinsics from left->right test:" << endl; - extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::LEFT, dai::CameraBoardSocket::RIGHT); + extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::CAM_B, dai::CameraBoardSocket::CAM_C); printMatrix(extrinsics); cout << "Extrinsics from right->left test:" << endl; - extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::RIGHT, dai::CameraBoardSocket::LEFT); + extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::CAM_C, dai::CameraBoardSocket::CAM_B); printMatrix(extrinsics); cout << "Extrinsics from right->rgb test:" << endl; - extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::RIGHT, dai::CameraBoardSocket::RGB); + extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::CAM_C, dai::CameraBoardSocket::CAM_A); printMatrix(extrinsics); cout << "Extrinsics from rgb->right test:" << endl; - extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::RGB, dai::CameraBoardSocket::RIGHT); + extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::CAM_A, dai::CameraBoardSocket::CAM_C); printMatrix(extrinsics); cout << "Extrinsics from left->rgb test:" << endl; - extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::LEFT, dai::CameraBoardSocket::RGB); + extrinsics = calibData.getCameraExtrinsics(dai::CameraBoardSocket::CAM_B, dai::CameraBoardSocket::CAM_A); printMatrix(extrinsics); return 0; diff --git a/examples/host_side/device_logging.cpp b/examples/host_side/device_logging.cpp new file mode 100644 index 000000000..bb7043116 --- /dev/null +++ b/examples/host_side/device_logging.cpp @@ -0,0 +1,41 @@ +#include +#include + +// Includes common necessary includes for development using depthai library +#include "depthai/depthai.hpp" + +int main() { + using namespace std; + using namespace std::chrono_literals; + + // Create a log file + ofstream logstream{"device.log"}; + + // Connect to device and start pipeline + dai::Device::Config config; + config.logLevel = dai::LogLevel::DEBUG; + config.outputLogLevel = dai::LogLevel::WARN; + config.board.logDevicePrints = true; + dai::Device device(config, dai::UsbSpeed::SUPER); + + // Configure logging + device.addLogCallback([&logstream](dai::LogMessage msg) { + logstream << "[" << msg.nodeIdName << "] " << msg.payload << endl; + cout << "[LOGGED] [" << msg.nodeIdName << "] " << msg.payload << endl; + }); + + // Print available sensors + cout << "Available camera sensors: "; + for(auto& sensor : device.getCameraSensorNames()) { + cout << "Socket: " << sensor.first << " - " << sensor.second << ", "; + } + cout << endl; + + // Print device name + cout << "Device name: " << device.getDeviceName() << endl; + + // Wait a tad for some logs to arrive + this_thread::sleep_for(3s); + + return 0; +} diff --git a/examples/host_side/opencv_support.cpp b/examples/host_side/opencv_support.cpp index 57970f339..3560107c8 100644 --- a/examples/host_side/opencv_support.cpp +++ b/examples/host_side/opencv_support.cpp @@ -20,7 +20,7 @@ int main() { // Properties camRgb->setPreviewSize(300, 300); - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setInterleaved(true); camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); diff --git a/examples/host_side/queue_add_callback.cpp b/examples/host_side/queue_add_callback.cpp index 1f798b2bd..aa91d4264 100644 --- a/examples/host_side/queue_add_callback.cpp +++ b/examples/host_side/queue_add_callback.cpp @@ -24,9 +24,9 @@ int main() { // Properties camRgb->setPreviewSize(300, 300); - left->setBoardSocket(dai::CameraBoardSocket::LEFT); + left->setCamera("left"); left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + right->setCamera("right"); right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); // Stream all the camera streams through the same XLink node diff --git a/examples/mixed/frame_sync.cpp b/examples/mixed/frame_sync.cpp index f3e40557e..8609e9be6 100644 --- a/examples/mixed/frame_sync.cpp +++ b/examples/mixed/frame_sync.cpp @@ -19,12 +19,12 @@ int main() { auto left = pipeline.create(); left->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - left->setBoardSocket(dai::CameraBoardSocket::LEFT); + left->setCamera("left"); left->setFps(FPS); auto right = pipeline.create(); right->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - right->setBoardSocket(dai::CameraBoardSocket::RIGHT); + right->setCamera("right"); right->setFps(FPS); auto stereo = pipeline.create(); @@ -32,7 +32,7 @@ int main() { stereo->setLeftRightCheck(true); stereo->setExtendedDisparity(false); stereo->setSubpixel(false); - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); left->out.link(stereo->left); right->out.link(stereo->right); diff --git a/examples/mixed/mono_depth_mobilenetssd.cpp b/examples/mixed/mono_depth_mobilenetssd.cpp index e8aa2eb7b..cb1f90d7e 100644 --- a/examples/mixed/mono_depth_mobilenetssd.cpp +++ b/examples/mixed/mono_depth_mobilenetssd.cpp @@ -41,9 +41,9 @@ int main(int argc, char** argv) { nnOut->setStreamName("nn"); // Properties - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); // Produce the depth map (using disparity output as it's easier to visualize depth this way) stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); diff --git a/examples/mixed/multiple_devices.cpp b/examples/mixed/multiple_devices.cpp index ca4b1cba3..03ed54ada 100644 --- a/examples/mixed/multiple_devices.cpp +++ b/examples/mixed/multiple_devices.cpp @@ -11,7 +11,7 @@ std::shared_ptr createPipeline() { auto camRgb = pipeline->create(); camRgb->setPreviewSize(300, 300); - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setInterleaved(false); diff --git a/examples/mixed/rgb_encoding_mobilenet.cpp b/examples/mixed/rgb_encoding_mobilenet.cpp index e335c57f3..f3159df73 100644 --- a/examples/mixed/rgb_encoding_mobilenet.cpp +++ b/examples/mixed/rgb_encoding_mobilenet.cpp @@ -39,7 +39,7 @@ int main(int argc, char** argv) { nnOut->setStreamName("nn"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setPreviewSize(300, 300); camRgb->setInterleaved(false); diff --git a/examples/mixed/rgb_encoding_mono_mobilenet.cpp b/examples/mixed/rgb_encoding_mono_mobilenet.cpp index 2a3bba780..f8d0980be 100644 --- a/examples/mixed/rgb_encoding_mono_mobilenet.cpp +++ b/examples/mixed/rgb_encoding_mono_mobilenet.cpp @@ -43,9 +43,9 @@ int main(int argc, char** argv) { nnOut->setStreamName("nn"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_720_P); videoEncoder->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H265_MAIN); diff --git a/examples/mixed/rgb_encoding_mono_mobilenet_depth.cpp b/examples/mixed/rgb_encoding_mono_mobilenet_depth.cpp index ff2eadd0d..3e0573089 100644 --- a/examples/mixed/rgb_encoding_mono_mobilenet_depth.cpp +++ b/examples/mixed/rgb_encoding_mono_mobilenet_depth.cpp @@ -48,11 +48,11 @@ int main(int argc, char** argv) { nnOut->setStreamName("nn"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); videoEncoder->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H265_MAIN); diff --git a/include/depthai/common/CameraBoardSocket.hpp b/include/depthai/common/CameraBoardSocket.hpp index c2fa18bf3..9802a2e6b 100644 --- a/include/depthai/common/CameraBoardSocket.hpp +++ b/include/depthai/common/CameraBoardSocket.hpp @@ -10,14 +10,14 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraBoardSocket& case dai::CameraBoardSocket::AUTO: out << "AUTO"; break; - case dai::CameraBoardSocket::RGB: - out << "RGB/CENTER/CAM_A"; + case dai::CameraBoardSocket::CAM_A: + out << "CAM_A"; break; - case dai::CameraBoardSocket::LEFT: - out << "LEFT/CAM_B"; + case dai::CameraBoardSocket::CAM_B: + out << "CAM_B"; break; - case dai::CameraBoardSocket::RIGHT: - out << "RIGHT/CAM_C"; + case dai::CameraBoardSocket::CAM_C: + out << "CAM_C"; break; case dai::CameraBoardSocket::CAM_D: out << "CAM_D"; @@ -34,6 +34,12 @@ inline std::ostream& operator<<(std::ostream& out, const dai::CameraBoardSocket& case dai::CameraBoardSocket::CAM_H: out << "CAM_H"; break; + case dai::CameraBoardSocket::CAM_I: + out << "CAM_I"; + break; + case dai::CameraBoardSocket::CAM_J: + out << "CAM_J"; + break; } return out; } diff --git a/include/depthai/device/CalibrationHandler.hpp b/include/depthai/device/CalibrationHandler.hpp index 723bbf9e5..04ba756dd 100644 --- a/include/depthai/device/CalibrationHandler.hpp +++ b/include/depthai/device/CalibrationHandler.hpp @@ -226,16 +226,16 @@ class CalibrationHandler { std::vector getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const; /** - * Get the baseline distance between two specified cameras. By default it will get the baseline between CameraBoardSocket.RIGHT - * and CameraBoardSocket.LEFT. + * Get the baseline distance between two specified cameras. By default it will get the baseline between CameraBoardSocket.CAM_C + * and CameraBoardSocket.CAM_B. * * @param cam1 First camera * @param cam2 Second camera * @param useSpecTranslation Enabling this bool uses the translation information from the board design data (not the calibration data) * @return baseline distance in centimeters */ - float getBaselineDistance(CameraBoardSocket cam1 = CameraBoardSocket::RIGHT, - CameraBoardSocket cam2 = CameraBoardSocket::LEFT, + float getBaselineDistance(CameraBoardSocket cam1 = CameraBoardSocket::CAM_C, + CameraBoardSocket cam2 = CameraBoardSocket::CAM_B, bool useSpecTranslation = true) const; /** diff --git a/include/depthai/device/Device.hpp b/include/depthai/device/Device.hpp index 39bb8921c..32ae74f45 100644 --- a/include/depthai/device/Device.hpp +++ b/include/depthai/device/Device.hpp @@ -34,7 +34,7 @@ class Device : public DeviceBase { * @param usb2Mode (bool) Boot device using USB2 mode firmware */ template ::value, bool> = true> - Device(const Pipeline& pipeline, T usb2Mode); + [[deprecated("Use constructor taking 'UsbSpeed' instead")]] Device(const Pipeline& pipeline, T usb2Mode); /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. @@ -64,7 +64,7 @@ class Device : public DeviceBase { * @param usb2Mode (bool) Boot device using USB2 mode firmware */ template ::value, bool> = true> - Device(const Pipeline& pipeline, const DeviceInfo& devInfo, T usb2Mode); + [[deprecated("Use constructor taking 'UsbSpeed' instead")]] Device(const Pipeline& pipeline, const DeviceInfo& devInfo, T usb2Mode); /** * Connects to device specified by devInfo. diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index 53467f3d4..561c095bb 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -22,6 +22,7 @@ #include "depthai/device/Version.hpp" #include "depthai/openvino/OpenVINO.hpp" #include "depthai/utility/Pimpl.hpp" +#include "depthai/utility/ProfilingData.hpp" #include "depthai/xlink/XLinkConnection.hpp" #include "depthai/xlink/XLinkStream.hpp" @@ -69,6 +70,8 @@ class DeviceBase { OpenVINO::Version version = OpenVINO::VERSION_UNIVERSAL; BoardConfig board; bool nonExclusiveMode = false; + tl::optional outputLogLevel; + tl::optional logLevel; }; // static API @@ -146,6 +149,13 @@ class DeviceBase { */ static std::vector getEmbeddedDeviceBinary(Config config); + /** + * Get current global accumulated profiling data + * + * @returns ProfilingData from all devices + */ + static ProfilingData getGlobalProfilingData(); + /** * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. * @param pipeline Pipeline to be executed on the device @@ -321,6 +331,53 @@ class DeviceBase { */ DeviceBase(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed); + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param config Config with which the device will be booted with + * @param usb2Mode Boot device using USB2 mode firmware + */ + template ::value, bool> = true> + DeviceBase(Config config, T usb2Mode) : DeviceBase(config, usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED) {} + + /** + * Connects to device specified by devInfo. + * @param config Config with which the device will be booted with + * @param maxUsbSpeed Maximum allowed USB speed + */ + DeviceBase(Config config, UsbSpeed maxUsbSpeed); + + /** + * Connects to any available device with a DEFAULT_SEARCH_TIME timeout. + * @param config Config with which the device will be booted with + * @param pathToCmd Path to custom device firmware + */ + DeviceBase(Config config, const dai::Path& pathToCmd); + + /** + * Connects to device specified by devInfo. + * @param config Config with which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to + * @param usb2Mode Boot device using USB2 mode firmware + */ + template ::value, bool> = true> + DeviceBase(Config config, const DeviceInfo& devInfo, T usb2Mode) : DeviceBase(config, devInfo, usb2Mode ? UsbSpeed::HIGH : DeviceBase::DEFAULT_USB_SPEED) {} + + /** + * 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 maxUsbSpeed Maximum allowed USB speed + */ + DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); + + /** + * Connects to device specified by devInfo. + * @param config Config with which the device will be booted with + * @param devInfo DeviceInfo which specifies which device to connect to + * @param pathToCmd Path to custom device firmware + */ + DeviceBase(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd); + /** * Device destructor * @note In the destructor of the derived class, remember to call close() @@ -455,13 +512,20 @@ class DeviceBase { /** * Retrieves crash dump for debugging. */ - dai::CrashDump getCrashDump(); + dai::CrashDump getCrashDump(bool clearCrashDump = true); /** * Retrieves whether the is crash dump stored on device or not. */ bool hasCrashDump(); + /** + * Get current accumulated profiling data + * + * @returns ProfilingData from the specific device + */ + ProfilingData getProfilingData(); + /** * Add a callback for device logging. The callback will be called from a separate thread with the LogMessage being passed. * @@ -798,12 +862,31 @@ class DeviceBase { */ virtual void closeImpl(); - private: - // private functions + protected: + // protected functions + 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(const Pipeline& pipeline, 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); + void init(const Pipeline& pipeline, const dai::Path& pathToCmd); + void init(const Pipeline& pipeline, const DeviceInfo& devInfo); + 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); + void init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed); + void init(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd); + + private: + // private functions void init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional pipeline); void tryGetDevice(); @@ -827,6 +910,10 @@ class DeviceBase { std::thread loggingThread; std::atomic loggingRunning{true}; + // Profiling thread + std::thread profilingThread; + std::atomic profilingRunning{true}; + // Monitor thread std::thread monitorThread; std::mutex lastWatchdogPingTimeMtx; diff --git a/include/depthai/pipeline/datatype/CameraControl.hpp b/include/depthai/pipeline/datatype/CameraControl.hpp index 2c5b51f60..c9606f817 100644 --- a/include/depthai/pipeline/datatype/CameraControl.hpp +++ b/include/depthai/pipeline/datatype/CameraControl.hpp @@ -275,6 +275,18 @@ class CameraControl : public Buffer { * Retrieves lens position, range 0..255. Returns -1 if not available */ int getLensPosition() const; + + /** + * Set explicit configuration. + * @param config Explicit configuration + */ + CameraControl& set(dai::RawCameraControl config); + + /** + * Retrieve configuration data for CameraControl. + * @returns config for CameraControl + */ + dai::RawCameraControl get() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/EdgeDetectorConfig.hpp b/include/depthai/pipeline/datatype/EdgeDetectorConfig.hpp index cca8bf5d8..f14a931e1 100644 --- a/include/depthai/pipeline/datatype/EdgeDetectorConfig.hpp +++ b/include/depthai/pipeline/datatype/EdgeDetectorConfig.hpp @@ -35,6 +35,18 @@ class EdgeDetectorConfig : public Buffer { * @returns EdgeDetectorConfigData: sobel filter horizontal and vertical 3x3 kernels */ EdgeDetectorConfigData getConfigData() const; + + /** + * Set explicit configuration. + * @param config Explicit configuration + */ + EdgeDetectorConfig& set(dai::RawEdgeDetectorConfig config); + + /** + * Retrieve configuration data for EdgeDetector. + * @returns config for EdgeDetector + */ + dai::RawEdgeDetectorConfig get() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ImageManipConfig.hpp b/include/depthai/pipeline/datatype/ImageManipConfig.hpp index aeab52c8f..34953579d 100644 --- a/include/depthai/pipeline/datatype/ImageManipConfig.hpp +++ b/include/depthai/pipeline/datatype/ImageManipConfig.hpp @@ -242,6 +242,18 @@ class ImageManipConfig : public Buffer { * @returns specified colormap */ Colormap getColormap() const; + + /** + * Set explicit configuration. + * @param config Explicit configuration + */ + ImageManipConfig& set(dai::RawImageManipConfig config); + + /** + * Retrieve configuration data for ImageManip. + * @returns config for ImageManip + */ + dai::RawImageManipConfig get() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/SpatialLocationCalculatorConfig.hpp b/include/depthai/pipeline/datatype/SpatialLocationCalculatorConfig.hpp index 6c3ae5994..740c6ff4d 100644 --- a/include/depthai/pipeline/datatype/SpatialLocationCalculatorConfig.hpp +++ b/include/depthai/pipeline/datatype/SpatialLocationCalculatorConfig.hpp @@ -39,6 +39,18 @@ class SpatialLocationCalculatorConfig : public Buffer { * @returns Vector of configuration parameters for ROIs (region of interests) */ std::vector getConfigData() const; + + /** + * Set explicit configuration. + * @param config Explicit configuration + */ + SpatialLocationCalculatorConfig& set(dai::RawSpatialLocationCalculatorConfig config); + + /** + * Retrieve configuration data for SpatialLocationCalculator. + * @returns config for SpatialLocationCalculator + */ + dai::RawSpatialLocationCalculatorConfig get() const; }; } // namespace dai diff --git a/include/depthai/pipeline/datatype/ToFConfig.hpp b/include/depthai/pipeline/datatype/ToFConfig.hpp new file mode 100644 index 000000000..39a8adf08 --- /dev/null +++ b/include/depthai/pipeline/datatype/ToFConfig.hpp @@ -0,0 +1,47 @@ +#pragma once + +#include +#include + +#include "depthai-shared/datatype/RawToFConfig.hpp" +#include "depthai/pipeline/datatype/Buffer.hpp" + +namespace dai { + +/** + * ToFConfig message. Carries config for feature tracking algorithm + */ +class ToFConfig : public Buffer { + std::shared_ptr serialize() const override; + RawToFConfig& cfg; + + public: + // Raw* mirror + using DepthParams = RawToFConfig::DepthParams; + + /** + * Construct ToFConfig message. + */ + ToFConfig(); + explicit ToFConfig(std::shared_ptr ptr); + virtual ~ToFConfig() = default; + + ToFConfig& setDepthParams(dai::ToFConfig::DepthParams config); + ToFConfig& setFreqModUsed(dai::ToFConfig::DepthParams::TypeFMod fmod); + ToFConfig& setAvgPhaseShuffle(bool enable); + ToFConfig& setMinAmplitude(float minamp); + + /** + * Set explicit configuration. + * @param config Explicit configuration + */ + ToFConfig& set(dai::RawToFConfig config); + + /** + * Retrieve configuration data for ToF. + * @returns config for feature tracking algorithm + */ + dai::RawToFConfig get() const; +}; + +} // namespace dai diff --git a/include/depthai/pipeline/datatypes.hpp b/include/depthai/pipeline/datatypes.hpp index 8cce71f43..b16c8f89e 100644 --- a/include/depthai/pipeline/datatypes.hpp +++ b/include/depthai/pipeline/datatypes.hpp @@ -18,5 +18,6 @@ #include "datatype/SpatialLocationCalculatorData.hpp" #include "datatype/StereoDepthConfig.hpp" #include "datatype/SystemInformation.hpp" +#include "datatype/ToFConfig.hpp" #include "datatype/TrackedFeatures.hpp" #include "datatype/Tracklets.hpp" diff --git a/include/depthai/pipeline/node/Camera.hpp b/include/depthai/pipeline/node/Camera.hpp index 5ea4ec6b5..bb44afa68 100644 --- a/include/depthai/pipeline/node/Camera.hpp +++ b/include/depthai/pipeline/node/Camera.hpp @@ -334,6 +334,17 @@ class Camera : public NodeCRTP { void setCalibrationAlpha(float alpha); /// Get calibration alpha parameter that determines FOV of undistorted frames float getCalibrationAlpha() const; + + /** + * Configures whether the camera `raw` frames are saved as MIPI-packed to memory. + * The packed format is more efficient, consuming less memory on device, and less data + * to send to host: RAW10: 4 pixels saved on 5 bytes, RAW12: 2 pixels saved on 3 bytes. + * When packing is disabled (`false`), data is saved lsb-aligned, e.g. a RAW10 pixel + * will be stored as uint16, on bits 9..0: 0b0000'00pp'pppp'pppp. + * Default is auto: enabled for standard color/monochrome cameras where ISP can work + * with both packed/unpacked, but disabled for other cameras like ToF. + */ + void setRawOutputPacked(bool packed); }; } // namespace node diff --git a/include/depthai/pipeline/node/ColorCamera.hpp b/include/depthai/pipeline/node/ColorCamera.hpp index 1e36cfba3..dc2e1b2e2 100644 --- a/include/depthai/pipeline/node/ColorCamera.hpp +++ b/include/depthai/pipeline/node/ColorCamera.hpp @@ -340,6 +340,17 @@ class ColorCamera : public NodeCRTP { int getRawNumFramesPool(); /// Get number of frames in isp pool int getIspNumFramesPool(); + + /** + * Configures whether the camera `raw` frames are saved as MIPI-packed to memory. + * The packed format is more efficient, consuming less memory on device, and less data + * to send to host: RAW10: 4 pixels saved on 5 bytes, RAW12: 2 pixels saved on 3 bytes. + * When packing is disabled (`false`), data is saved lsb-aligned, e.g. a RAW10 pixel + * will be stored as uint16, on bits 9..0: 0b0000'00pp'pppp'pppp. + * Default is auto: enabled for standard color/monochrome cameras where ISP can work + * with both packed/unpacked, but disabled for other cameras like ToF. + */ + void setRawOutputPacked(bool packed); }; } // namespace node diff --git a/include/depthai/pipeline/node/MonoCamera.hpp b/include/depthai/pipeline/node/MonoCamera.hpp index 7b1348ca8..d6c6c8b52 100644 --- a/include/depthai/pipeline/node/MonoCamera.hpp +++ b/include/depthai/pipeline/node/MonoCamera.hpp @@ -149,6 +149,17 @@ class MonoCamera : public NodeCRTP { int getNumFramesPool() const; /// Get number of frames in raw pool int getRawNumFramesPool() const; + + /** + * Configures whether the camera `raw` frames are saved as MIPI-packed to memory. + * The packed format is more efficient, consuming less memory on device, and less data + * to send to host: RAW10: 4 pixels saved on 5 bytes, RAW12: 2 pixels saved on 3 bytes. + * When packing is disabled (`false`), data is saved lsb-aligned, e.g. a RAW10 pixel + * will be stored as uint16, on bits 9..0: 0b0000'00pp'pppp'pppp. + * Default is auto: enabled for standard color/monochrome cameras where ISP can work + * with both packed/unpacked, but disabled for other cameras like ToF. + */ + void setRawOutputPacked(bool packed); }; } // namespace node diff --git a/include/depthai/pipeline/node/ToF.hpp b/include/depthai/pipeline/node/ToF.hpp new file mode 100644 index 000000000..2f4e055e0 --- /dev/null +++ b/include/depthai/pipeline/node/ToF.hpp @@ -0,0 +1,55 @@ +#pragma once + +#include "depthai/pipeline/Node.hpp" + +// shared +#include + +#include "depthai/pipeline/datatype/ToFConfig.hpp" + +namespace dai { +namespace node { + +/** + * @brief ToF node + */ +class ToF : public NodeCRTP { + public: + constexpr static const char* NAME = "ToF"; + + protected: + Properties& getProperties(); + + private: + std::shared_ptr rawConfig; + + /** + * Constructs ToF node. + */ + public: + ToF(const std::shared_ptr& par, int64_t nodeId); + ToF(const std::shared_ptr& par, int64_t nodeId, std::unique_ptr props); + + /** + * Initial config to use for depth calculation. + */ + ToFConfig initialConfig; + + /** + * Input ToF message with ability to modify parameters in runtime. + * Default queue is non-blocking with size 4. + */ + Input inputConfig{*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ToFConfig, false}}}; + + Input input{*this, "input", Input::Type::SReceiver, true, 8, {{DatatypeEnum::ImgFrame, true}}}; + + /** + * Outputs ImgFrame message that carries modified image. + */ + Output depth{*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, true}}}; + Output amplitude{*this, "amplitude", Output::Type::MSender, {{DatatypeEnum::ImgFrame, true}}}; + Output error{*this, "error", Output::Type::MSender, {{DatatypeEnum::ImgFrame, true}}}; +}; + +} // namespace node +} // namespace dai diff --git a/include/depthai/pipeline/node/UVC.hpp b/include/depthai/pipeline/node/UVC.hpp new file mode 100644 index 000000000..65fd84e27 --- /dev/null +++ b/include/depthai/pipeline/node/UVC.hpp @@ -0,0 +1,40 @@ +#pragma once + +#include + +// shared +#include + +namespace dai { +namespace node { + +/** + * @brief UVC (USB Video Class) node + */ +class UVC : public NodeCRTP { + public: + constexpr static const char* NAME = "UVC"; + + public: + UVC(const std::shared_ptr& par, int64_t nodeId); + UVC(const std::shared_ptr& par, int64_t nodeId, std::unique_ptr props); + + /** + * Input for image frames to be streamed over UVC + * + * Default queue is blocking with size 8 + */ + Input input{*this, "in", Input::Type::SReceiver, true, 8, true, {{DatatypeEnum::Buffer, true}}}; + + /// Set GPIO list for GPIOs to set (on/off) at init + void setGpiosOnInit(std::unordered_map list); + + /// Set GPIO list for GPIOs to set when streaming is enabled + void setGpiosOnStreamOn(std::unordered_map list); + + /// Set GPIO list for GPIOs to set when streaming is disabled + void setGpiosOnStreamOff(std::unordered_map list); +}; + +} // namespace node +} // namespace dai diff --git a/include/depthai/pipeline/nodes.hpp b/include/depthai/pipeline/nodes.hpp index cc7c6e749..bf0a3dc76 100644 --- a/include/depthai/pipeline/nodes.hpp +++ b/include/depthai/pipeline/nodes.hpp @@ -2,6 +2,7 @@ // all the nodes #include "node/AprilTag.hpp" +#include "node/Camera.hpp" #include "node/ColorCamera.hpp" #include "node/DetectionNetwork.hpp" #include "node/DetectionParser.hpp" @@ -19,6 +20,7 @@ #include "node/SpatialLocationCalculator.hpp" #include "node/StereoDepth.hpp" #include "node/SystemLogger.hpp" +#include "node/ToF.hpp" #include "node/VideoEncoder.hpp" #include "node/Warp.hpp" #include "node/XLinkIn.hpp" diff --git a/include/depthai/utility/ProfilingData.hpp b/include/depthai/utility/ProfilingData.hpp new file mode 100644 index 000000000..cb182cabd --- /dev/null +++ b/include/depthai/utility/ProfilingData.hpp @@ -0,0 +1,10 @@ +#pragma once + +namespace dai { + +struct ProfilingData { + long long numBytesWritten; + long long numBytesRead; +}; + +} // namespace dai diff --git a/include/depthai/xlink/XLinkConnection.hpp b/include/depthai/xlink/XLinkConnection.hpp index 7c65a8c05..1696e164a 100644 --- a/include/depthai/xlink/XLinkConnection.hpp +++ b/include/depthai/xlink/XLinkConnection.hpp @@ -14,6 +14,7 @@ // project #include "depthai/utility/Path.hpp" +#include "depthai/utility/ProfilingData.hpp" // Libraries #include @@ -84,6 +85,13 @@ class XLinkConnection { */ static DeviceInfo bootBootloader(const DeviceInfo& devInfo); + /** + * Get current accumulated profiling data + * + * @returns ProfilingData from the specific connection + */ + static ProfilingData getGlobalProfilingData(); + XLinkConnection(const DeviceInfo& deviceDesc, std::vector mvcmdBinary, XLinkDeviceState_t expectedState = X_LINK_BOOTED); XLinkConnection(const DeviceInfo& deviceDesc, dai::Path pathToMvcmd, XLinkDeviceState_t expectedState = X_LINK_BOOTED); explicit XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState = X_LINK_BOOTED); @@ -111,6 +119,13 @@ class XLinkConnection { */ bool isClosed() const; + /** + * Get current accumulated profiling data + * + * @returns ProfilingData from the specific connection + */ + ProfilingData getProfilingData(); + private: friend struct XLinkReadError; friend struct XLinkWriteError; diff --git a/package.xml b/package.xml index 266fe9b35..dae23a4f1 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ depthai - 2.21.2 + 2.22.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 aa3e0564c..f03e9d9b0 160000 --- a/shared/depthai-shared +++ b/shared/depthai-shared @@ -1 +1 @@ -Subproject commit aa3e0564c0de3ef66cb6b240ff2b65ed3ed70aba +Subproject commit f03e9d9b08df2c0a50b8a928901ce95b14f9c174 diff --git a/src/device/CalibrationHandler.cpp b/src/device/CalibrationHandler.cpp index 729a778da..15a4b6a29 100644 --- a/src/device/CalibrationHandler.cpp +++ b/src/device/CalibrationHandler.cpp @@ -15,6 +15,7 @@ #include "depthai-shared/common/Point3f.hpp" #include "nlohmann/json.hpp" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" #include "utility/matrixOps.hpp" namespace dai { @@ -94,8 +95,8 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path } nlohmann::json boardConfigData = nlohmann::json::parse(boardConfigStream); - CameraBoardSocket left = CameraBoardSocket::LEFT; - CameraBoardSocket right = CameraBoardSocket::RIGHT; + CameraBoardSocket left = CameraBoardSocket::CAM_B; + CameraBoardSocket right = CameraBoardSocket::CAM_C; if(boardConfigData.contains("board_config")) { eepromData.boardName = boardConfigData.at("board_config").at("name").get(); @@ -104,13 +105,13 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path eepromData.version = 6; if(!swapLeftRightCam) { - right = CameraBoardSocket::LEFT; - left = CameraBoardSocket::RIGHT; + right = CameraBoardSocket::CAM_B; + left = CameraBoardSocket::CAM_C; } eepromData.cameraData[right].specHfovDeg = boardConfigData.at("board_config").at("left_fov_deg").get(); eepromData.cameraData[left].specHfovDeg = boardConfigData.at("board_config").at("left_fov_deg").get(); - eepromData.cameraData[CameraBoardSocket::RGB].specHfovDeg = boardConfigData.at("board_config").at("rgb_fov_deg").get(); + eepromData.cameraData[CameraBoardSocket::CAM_A].specHfovDeg = boardConfigData.at("board_config").at("rgb_fov_deg").get(); eepromData.cameraData[left].extrinsics.specTranslation.x = -boardConfigData.at("board_config").at("left_to_right_distance_cm").get(); eepromData.cameraData[left].extrinsics.specTranslation.y = 0; @@ -143,11 +144,11 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path eepromData.cameraData[left].intrinsicMatrix = matrixConv(calibrationBuff, 18); eepromData.cameraData[right].intrinsicMatrix = matrixConv(calibrationBuff, 27); - eepromData.cameraData[CameraBoardSocket::RGB].intrinsicMatrix = matrixConv(calibrationBuff, 48); // 9*5 + 3 + eepromData.cameraData[CameraBoardSocket::CAM_A].intrinsicMatrix = matrixConv(calibrationBuff, 48); // 9*5 + 3 eepromData.cameraData[left].cameraType = CameraModel::Perspective; eepromData.cameraData[right].cameraType = CameraModel::Perspective; - eepromData.cameraData[CameraBoardSocket::RGB].cameraType = CameraModel::Perspective; // 9*5 + 3 + eepromData.cameraData[CameraBoardSocket::CAM_A].cameraType = CameraModel::Perspective; // 9*5 + 3 eepromData.cameraData[left].width = 1280; eepromData.cameraData[left].height = 800; @@ -155,12 +156,12 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path eepromData.cameraData[right].width = 1280; eepromData.cameraData[right].height = 800; - eepromData.cameraData[CameraBoardSocket::RGB].width = 1920; - eepromData.cameraData[CameraBoardSocket::RGB].height = 1080; + eepromData.cameraData[CameraBoardSocket::CAM_A].width = 1920; + eepromData.cameraData[CameraBoardSocket::CAM_A].height = 1080; eepromData.cameraData[left].distortionCoeff = std::vector(calibrationBuff.begin() + 69, calibrationBuff.begin() + 83); // 69 + 14 eepromData.cameraData[right].distortionCoeff = std::vector(calibrationBuff.begin() + 83, calibrationBuff.begin() + 69 + (2 * 14)); - eepromData.cameraData[CameraBoardSocket::RGB].distortionCoeff = + eepromData.cameraData[CameraBoardSocket::CAM_A].distortionCoeff = std::vector(calibrationBuff.begin() + 69 + (2 * 14), calibrationBuff.begin() + 69 + (3 * 14)); eepromData.cameraData[left].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 36); @@ -171,7 +172,7 @@ CalibrationHandler::CalibrationHandler(dai::Path calibrationDataPath, dai::Path eepromData.cameraData[left].extrinsics.translation.z = calibrationBuff[47]; eepromData.cameraData[right].extrinsics.rotationMatrix = matrixConv(calibrationBuff, 57); - eepromData.cameraData[right].extrinsics.toCameraSocket = CameraBoardSocket::RGB; + eepromData.cameraData[right].extrinsics.toCameraSocket = CameraBoardSocket::CAM_A; eepromData.cameraData[right].extrinsics.translation.x = -calibrationBuff[66]; eepromData.cameraData[right].extrinsics.translation.y = -calibrationBuff[67]; @@ -741,10 +742,10 @@ void CalibrationHandler::setStereoRight(CameraBoardSocket cameraId, std::vector< bool CalibrationHandler::validateCameraArray() const { if(eepromData.cameraData.size() > 1) { - if(eepromData.cameraData.find(dai::CameraBoardSocket::LEFT) != eepromData.cameraData.end()) { - return checkSrcLinks(dai::CameraBoardSocket::LEFT) || checkSrcLinks(dai::CameraBoardSocket::RIGHT); + if(eepromData.cameraData.find(dai::CameraBoardSocket::CAM_B) != eepromData.cameraData.end()) { + return checkSrcLinks(dai::CameraBoardSocket::CAM_B) || checkSrcLinks(dai::CameraBoardSocket::CAM_C); } else { - spdlog::debug( + logger::debug( "make sure the head of the Extrinsics is your left camera. Please cross check the data by creating a json file using " "eepromToJsonFile(). "); return false; @@ -760,14 +761,14 @@ bool CalibrationHandler::checkSrcLinks(CameraBoardSocket headSocket) const { while(headSocket != CameraBoardSocket::AUTO) { if(eepromData.cameraData.find(headSocket) == eepromData.cameraData.end()) { - spdlog::debug( + logger::debug( "Found link to a CameraID whose camera calibration is not loaded. Please cross check the connection by creating a json file using " "eepromToJsonFile(). "); isConnectionValidated = false; break; } if(marked.find(headSocket) != marked.end()) { - spdlog::debug( + logger::debug( "Loop found in extrinsics connection. Please cross check that the extrinsics are connected in an array in single direction by creating " "a json file using eepromToJsonFile(). "); isConnectionValidated = false; @@ -779,7 +780,7 @@ bool CalibrationHandler::checkSrcLinks(CameraBoardSocket headSocket) const { if(isConnectionValidated && eepromData.cameraData.size() != marked.size()) { isConnectionValidated = false; - spdlog::debug("Extrinsics between all the cameras is not found with single head and a tail"); + logger::debug("Extrinsics between all the cameras is not found with single head and a tail"); } return isConnectionValidated; } diff --git a/src/device/DataQueue.cpp b/src/device/DataQueue.cpp index 3285df171..7e1496fa0 100644 --- a/src/device/DataQueue.cpp +++ b/src/device/DataQueue.cpp @@ -13,7 +13,7 @@ #include "depthai-shared/xlink/XLinkConstants.hpp" // libraries -#include "spdlog/spdlog.h" +#include "utility/Logging.hpp" // Additions #include "spdlog/fmt/bin_to_hex.h" @@ -40,11 +40,11 @@ DataOutputQueue::DataOutputQueue(const std::shared_ptr conn, co const auto t2Parse = std::chrono::steady_clock::now(); // Trace level debugging - if(spdlog::get_level() == spdlog::level::trace) { + if(logger::get_level() == spdlog::level::trace) { std::vector metadata; DatatypeEnum type; data->getRaw()->serialize(metadata, type); - spdlog::trace("Received message from device ({}) - parsing time: {}, data size: {}, object type: {} object data: {}", + logger::trace("Received message from device ({}) - parsing time: {}, data size: {}, object type: {} object data: {}", name, std::chrono::duration_cast(t2Parse - t1Parse), data->getRaw()->data.size(), @@ -68,7 +68,7 @@ DataOutputQueue::DataOutputQueue(const std::shared_ptr conn, co try { callback(name, data); } catch(const std::exception& ex) { - spdlog::error("Callback with id: {} throwed an exception: {}", kv.first, ex.what()); + logger::error("Callback with id: {} throwed an exception: {}", kv.first, ex.what()); } } } @@ -102,7 +102,7 @@ void DataOutputQueue::close() { if((readingThread.get_id() != std::this_thread::get_id()) && readingThread.joinable()) readingThread.join(); // Log - spdlog::debug("DataOutputQueue ({}) closed", name); + logger::debug("DataOutputQueue ({}) closed", name); } DataOutputQueue::~DataOutputQueue() { @@ -196,11 +196,11 @@ DataInputQueue::DataInputQueue( auto t2Parse = std::chrono::steady_clock::now(); // Trace level debugging - if(spdlog::get_level() == spdlog::level::trace) { + if(logger::get_level() == spdlog::level::trace) { std::vector metadata; DatatypeEnum type; data->serialize(metadata, type); - spdlog::trace("Sending message to device ({}) - serialize time: {}, data size: {}, object type: {} object data: {}", + logger::trace("Sending message to device ({}) - serialize time: {}, data size: {}, object type: {} object data: {}", name, std::chrono::duration_cast(t2Parse - t1Parse), data->data.size(), @@ -243,7 +243,7 @@ void DataInputQueue::close() { if((writingThread.get_id() != std::this_thread::get_id()) && writingThread.joinable()) writingThread.join(); // Log - spdlog::debug("DataInputQueue ({}) closed", name); + logger::debug("DataInputQueue ({}) closed", name); } DataInputQueue::~DataInputQueue() { diff --git a/src/device/Device.cpp b/src/device/Device.cpp index eacc86230..feabee10f 100644 --- a/src/device/Device.cpp +++ b/src/device/Device.cpp @@ -23,40 +23,39 @@ namespace dai { // Common explicit instantiation, to remove the need to define in header constexpr std::size_t Device::EVENT_QUEUE_MAXIMUM_SIZE; -Device::Device(const Pipeline& pipeline) : DeviceBase(pipeline.getOpenVINOVersion()) { +Device::Device(const Pipeline& pipeline) : DeviceBase(pipeline.getDeviceConfig()) { tryStartPipeline(pipeline); } template ::value, bool>> -Device::Device(const Pipeline& pipeline, T usb2Mode) : DeviceBase(pipeline.getOpenVINOVersion(), usb2Mode) { +Device::Device(const Pipeline& pipeline, T usb2Mode) : DeviceBase(pipeline.getDeviceConfig(), usb2Mode) { tryStartPipeline(pipeline); } template Device::Device(const Pipeline&, bool); -Device::Device(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) : DeviceBase(pipeline.getOpenVINOVersion(), maxUsbSpeed) { +Device::Device(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) : DeviceBase(pipeline.getDeviceConfig(), maxUsbSpeed) { tryStartPipeline(pipeline); } -Device::Device(const Pipeline& pipeline, const dai::Path& pathToCmd) : DeviceBase(pipeline.getOpenVINOVersion(), pathToCmd) { +Device::Device(const Pipeline& pipeline, const dai::Path& pathToCmd) : DeviceBase(pipeline.getDeviceConfig(), pathToCmd) { tryStartPipeline(pipeline); } -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, false) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo) : DeviceBase(pipeline.getDeviceConfig(), devInfo, false) { tryStartPipeline(pipeline); } -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) - : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, pathToCmd) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : DeviceBase(pipeline.getDeviceConfig(), devInfo, pathToCmd) { tryStartPipeline(pipeline); } template ::value, bool>> -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, T usb2Mode) : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, usb2Mode) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, T usb2Mode) : DeviceBase(pipeline.getDeviceConfig(), devInfo, usb2Mode) { tryStartPipeline(pipeline); } template Device::Device(const Pipeline&, const DeviceInfo&, bool); -Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, maxUsbSpeed) { +Device::Device(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : DeviceBase(pipeline.getDeviceConfig(), devInfo, maxUsbSpeed) { tryStartPipeline(pipeline); } @@ -265,8 +264,10 @@ bool Device::startPipelineImpl(const Pipeline& pipeline) { } // Create DataInputQueue's + auto streamName = xlinkIn->getStreamName(); + if(inputQueueMap.count(streamName) != 0) throw std::invalid_argument(fmt::format("Streams have duplicate name '{}'", streamName)); // set max data size, for more verbosity - inputQueueMap[xlinkIn->getStreamName()] = std::make_shared(connection, xlinkIn->getStreamName(), 16, true, xlinkIn->getMaxDataSize()); + inputQueueMap[std::move(streamName)] = std::make_shared(connection, xlinkIn->getStreamName(), 16, true, xlinkIn->getMaxDataSize()); } for(const auto& kv : pipeline.getNodeMap()) { const auto& node = kv.second; @@ -275,29 +276,31 @@ bool Device::startPipelineImpl(const Pipeline& pipeline) { continue; } - auto streamName = xlinkOut->getStreamName(); // Create DataOutputQueue's + auto streamName = xlinkOut->getStreamName(); + if(outputQueueMap.count(streamName) != 0) throw std::invalid_argument(fmt::format("Streams have duplicate name '{}'", streamName)); outputQueueMap[streamName] = std::make_shared(connection, streamName); // Add callback for events - callbackIdMap[streamName] = outputQueueMap[streamName]->addCallback([this](std::string queueName, std::shared_ptr) { - { - // Lock first - std::unique_lock lock(eventMtx); - - // Check if size is equal or greater than EVENT_QUEUE_MAXIMUM_SIZE - if(eventQueue.size() >= EVENT_QUEUE_MAXIMUM_SIZE) { - auto numToRemove = eventQueue.size() - EVENT_QUEUE_MAXIMUM_SIZE + 1; - eventQueue.erase(eventQueue.begin(), eventQueue.begin() + numToRemove); - } + callbackIdMap[std::move(streamName)] = + outputQueueMap[xlinkOut->getStreamName()]->addCallback([this](std::string queueName, std::shared_ptr) { + { + // Lock first + std::unique_lock lock(eventMtx); + + // Check if size is equal or greater than EVENT_QUEUE_MAXIMUM_SIZE + if(eventQueue.size() >= EVENT_QUEUE_MAXIMUM_SIZE) { + auto numToRemove = eventQueue.size() - EVENT_QUEUE_MAXIMUM_SIZE + 1; + eventQueue.erase(eventQueue.begin(), eventQueue.begin() + numToRemove); + } - // Add to the end of event queue - eventQueue.push_back(std::move(queueName)); - } + // Add to the end of event queue + eventQueue.push_back(std::move(queueName)); + } - // notify the rest - eventCv.notify_all(); - }); + // notify the rest + eventCv.notify_all(); + }); } return DeviceBase::startPipelineImpl(pipeline); } diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 142df725c..607568ac0 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -35,6 +35,7 @@ #include "spdlog/fmt/chrono.h" #include "spdlog/sinks/stdout_color_sinks.h" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" namespace dai { @@ -122,7 +123,7 @@ std::chrono::milliseconds DeviceBase::getDefaultSearchTime() { try { defaultSearchTime = std::chrono::milliseconds{std::stoi(searchTimeStr)}; } catch(const std::invalid_argument& e) { - spdlog::warn("DEPTHAI_SEARCH_TIMEOUT value invalid: {}", e.what()); + logger::warn("DEPTHAI_SEARCH_TIMEOUT value invalid: {}", e.what()); } } @@ -178,12 +179,12 @@ std::tuple DeviceBase::getAnyAvailableDevice(std::chrono::mill for(const auto& invalidDevice : invalidDevices) { const auto& invalidDeviceInfo = invalidDevice.second; if(invalidDeviceInfo.status == X_LINK_INSUFFICIENT_PERMISSIONS) { - spdlog::warn("Insufficient permissions to communicate with {} device with name \"{}\". Make sure udev rules are set", + logger::warn("Insufficient permissions to communicate with {} device with name \"{}\". Make sure udev rules are set", XLinkDeviceStateToStr(invalidDeviceInfo.state), invalidDeviceInfo.name); } else { // Warn - spdlog::warn( + logger::warn( "Skipping {} device with name \"{}\" ({})", XLinkDeviceStateToStr(invalidDeviceInfo.state), invalidDeviceInfo.name, invalidDeviceInfo.mxid); } } @@ -252,6 +253,10 @@ std::vector DeviceBase::getEmbeddedDeviceBinary(Config config) { return Resources::getInstance().getDeviceFirmware(config); } +ProfilingData DeviceBase::getGlobalProfilingData() { + return XLinkConnection::getGlobalProfilingData(); +} + /* std::vector DeviceBase::getAllConnectedDevices(){ return XLinkConnection::getAllConnectedDevices(); @@ -273,7 +278,7 @@ class DeviceBase::Impl { // Default sink std::shared_ptr stdoutColorSink = std::make_shared(); // Device Logger - DeviceLogger logger{"", stdoutColorSink}; + DeviceLogger logger{"host", stdoutColorSink}; // RPC std::mutex rpcMutex; @@ -343,45 +348,128 @@ DeviceBase::DeviceBase(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed) : DeviceBase(OpenVINO::VERSION_UNIVERSAL, dai::DeviceInfo(std::move(nameOrDeviceId)), maxUsbSpeed) {} DeviceBase::DeviceBase(OpenVINO::Version version) { - tryGetDevice(); - init(version, false, ""); + init(version); } DeviceBase::DeviceBase(OpenVINO::Version version, const dai::Path& pathToCmd) { - tryGetDevice(); - init(version, false, pathToCmd); + init(version, pathToCmd); } DeviceBase::DeviceBase(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { - tryGetDevice(); - init(version, maxUsbSpeed, ""); + init(version, maxUsbSpeed); } -DeviceBase::DeviceBase(const Pipeline& pipeline) : DeviceBase(pipeline.getOpenVINOVersion()) { +DeviceBase::DeviceBase(const Pipeline& pipeline) { + init(pipeline); tryStartPipeline(pipeline); } -DeviceBase::DeviceBase(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) : DeviceBase(pipeline.getOpenVINOVersion(), maxUsbSpeed) { +DeviceBase::DeviceBase(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { + init(pipeline, maxUsbSpeed); tryStartPipeline(pipeline); } -DeviceBase::DeviceBase(const Pipeline& pipeline, const dai::Path& pathToCmd) : DeviceBase(pipeline.getOpenVINOVersion(), pathToCmd) { +DeviceBase::DeviceBase(const Pipeline& pipeline, const dai::Path& pathToCmd) { + init(pipeline, pathToCmd); tryStartPipeline(pipeline); } -DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo) - : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, DeviceBase::DEFAULT_USB_SPEED) {} +DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo) : deviceInfo(devInfo) { + init(pipeline, devInfo); + tryStartPipeline(pipeline); +} -DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) - : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, maxUsbSpeed) { +DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : deviceInfo(devInfo) { + init(pipeline, devInfo, maxUsbSpeed); tryStartPipeline(pipeline); } -DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) - : DeviceBase(pipeline.getOpenVINOVersion(), devInfo, pathToCmd) { +DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { + init(pipeline, devInfo, pathToCmd); tryStartPipeline(pipeline); } +DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : deviceInfo(devInfo) { + init(config, maxUsbSpeed, ""); +} + +DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) { + init(config, false, pathToCmd); +} + +DeviceBase::DeviceBase(Config config, const dai::Path& pathToCmd) { + init(config, pathToCmd); +} + +DeviceBase::DeviceBase(Config config, UsbSpeed maxUsbSpeed) { + init(config, maxUsbSpeed); +} + +void DeviceBase::init(OpenVINO::Version version) { + tryGetDevice(); + init(version, false, ""); +} + +void DeviceBase::init(OpenVINO::Version version, const dai::Path& pathToCmd) { + tryGetDevice(); + init(version, false, pathToCmd); +} + +void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) { + tryGetDevice(); + init(version, maxUsbSpeed, ""); +} + +void DeviceBase::init(const Pipeline& pipeline) { + tryGetDevice(); + init(pipeline, false, ""); +} + +void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) { + tryGetDevice(); + init(pipeline, maxUsbSpeed, ""); +} + +void DeviceBase::init(const Pipeline& pipeline, const dai::Path& pathToCmd) { + tryGetDevice(); + init(pipeline, false, pathToCmd); +} + +void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo) { + deviceInfo = devInfo; + init(pipeline, false, ""); +} + +void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { + deviceInfo = devInfo; + init(pipeline, maxUsbSpeed, ""); +} + +void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { + deviceInfo = devInfo; + init(pipeline, false, pathToCmd); +} + +void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) { + tryGetDevice(); + init(config, maxUsbSpeed, ""); +} + +void DeviceBase::init(Config config, const dai::Path& pathToCmd) { + tryGetDevice(); + init(config, false, pathToCmd); +} + +void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) { + deviceInfo = devInfo; + init(config, maxUsbSpeed, ""); +} + +void DeviceBase::init(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) { + deviceInfo = devInfo; + init(config, false, pathToCmd); +} + DeviceBase::DeviceBase(Config config) { tryGetDevice(); init2(config, {}, {}); @@ -402,7 +490,7 @@ void DeviceBase::close() { void DeviceBase::closeImpl() { using namespace std::chrono; auto t1 = steady_clock::now(); - spdlog::debug("Device about to be closed..."); + pimpl->logger.debug("Device about to be closed..."); // Close connection first; causes Xlink internal calls to unblock semaphore waits and // return error codes, which then allows queues to unblock @@ -415,6 +503,7 @@ void DeviceBase::closeImpl() { watchdogRunning = false; timesyncRunning = false; loggingRunning = false; + profilingRunning = false; // Stop watchdog first (this resets and waits for link to fall down) if(watchdogThread.joinable()) watchdogThread.join(); @@ -422,6 +511,8 @@ void DeviceBase::closeImpl() { if(timesyncThread.joinable()) timesyncThread.join(); // And at the end stop logging thread if(loggingThread.joinable()) loggingThread.join(); + // And at the end stop profiling thread + if(profilingThread.joinable()) profilingThread.join(); // At the end stop the monitor thread if(monitorThread.joinable()) monitorThread.join(); @@ -429,7 +520,7 @@ void DeviceBase::closeImpl() { pimpl->rpcStream = nullptr; pimpl->rpcClient = nullptr; - spdlog::debug("Device closed, {}", duration_cast(steady_clock::now() - t1).count()); + pimpl->logger.debug("Device closed, {}", duration_cast(steady_clock::now() - t1).count()); } // This function is thread-unsafe. The idea of "isClosed" is ephemerial and @@ -471,6 +562,12 @@ void DeviceBase::init(const Pipeline& pipeline, bool usb2Mode, const dai::Path& 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 @@ -485,6 +582,12 @@ void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed, const dai: cfg.board.usb.maxSpeed = maxUsbSpeed; init2(cfg, pathToMvcmd, pipeline); } +void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) { + Config cfg = config; + // Modify usb speed + cfg.board.usb.maxSpeed = maxUsbSpeed; + init2(cfg, pathToMvcmd, {}); +} void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional pipeline) { // Initalize depthai library if not already @@ -508,17 +611,17 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Found an actual device by given DeviceInfo: {}", deviceInfo.toString()); } else { deviceInfo.state = X_LINK_ANY_STATE; - spdlog::debug("Searched, but no actual device found by given DeviceInfo"); + pimpl->logger.debug("Searched, but no actual device found by given DeviceInfo"); } } if(pipeline) { - spdlog::debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(config.version)); + pimpl->logger.debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(config.version)); } else { - spdlog::debug("Device - OpenVINO version: {}", OpenVINO::getVersionName(config.version)); + pimpl->logger.debug("Device - OpenVINO version: {}", OpenVINO::getVersionName(config.version)); } // Set logging pattern of device (device id + shared pattern) @@ -537,12 +640,12 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(watchdog.count()); watchdogTimeout = watchdog; if(watchdogTimeout.count() == 0) { - spdlog::warn("Watchdog disabled! In case of unclean exit, the device needs reset or power-cycle for next run", watchdogTimeout); + pimpl->logger.warn("Watchdog disabled! In case of unclean exit, the device needs reset or power-cycle for next run", watchdogTimeout); } else { - spdlog::warn("Using a custom watchdog value of {}", watchdogTimeout); + pimpl->logger.warn("Using a custom watchdog value of {}", watchdogTimeout); } } catch(const std::invalid_argument& e) { - spdlog::warn("DEPTHAI_WATCHDOG value invalid: {}", e.what()); + pimpl->logger.warn("DEPTHAI_WATCHDOG value invalid: {}", e.what()); } } @@ -552,9 +655,9 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(watchdog.count()); - spdlog::warn("Watchdog initial delay set to {}", watchdog); + pimpl->logger.warn("Watchdog initial delay set to {}", watchdog); } catch(const std::invalid_argument& e) { - spdlog::warn("DEPTHAI_WATCHDOG_INITIAL_DELAY value invalid: {}", e.what()); + pimpl->logger.warn("DEPTHAI_WATCHDOG_INITIAL_DELAY value invalid: {}", e.what()); } } @@ -565,14 +668,14 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.warn("DEPTHAI_DEBUG value invalid: {}, should be a number (non-zero to enable)", e.what()); } } // Get embedded mvcmd or external with applied config - if(spdlog::get_level() == spdlog::level::debug) { + if(logger::get_level() == spdlog::level::debug) { nlohmann::json jBoardConfig = config.board; - spdlog::debug("Device - BoardConfig: {} \nlibnop:{}", jBoardConfig.dump(), spdlog::to_hex(utility::serialize(config.board))); + pimpl->logger.debug("Device - BoardConfig: {} \nlibnop:{}", jBoardConfig.dump(), spdlog::to_hex(utility::serialize(config.board))); } std::vector fwWithConfig = Resources::getInstance().getDeviceFirmware(config, pathToMvcmd); @@ -596,14 +699,14 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional(t2 - t1)); + pimpl->logger.debug("Booting FW with Bootloader. Version {}, Time taken: {}", version.toString(), duration_cast(t2 - t1)); // After that the state will be expectedBootState deviceInfo.state = expectedBootState; } else { // Boot into USB ROM BOOTLOADER bl.bootUsbRomBootloader(); - spdlog::debug("Booting FW by jumping to USB ROM Bootloader first. Bootloader Version {}", version.toString()); + pimpl->logger.debug("Booting FW by jumping to USB ROM Bootloader first. Bootloader Version {}", version.toString()); // After that the state will be UNBOOTED deviceInfo.state = X_LINK_UNBOOTED; @@ -632,8 +735,8 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional lock(pimpl->rpcMutex); // Log the request data - if(spdlog::get_level() == spdlog::level::trace) { - spdlog::trace("RPC: {}", nlohmann::json::from_msgpack(request).dump()); + if(logger::get_level() == spdlog::level::trace) { + pimpl->logger.trace("RPC: {}", nlohmann::json::from_msgpack(request).dump()); } try { @@ -645,7 +748,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionalread(); } catch(const std::exception& e) { // If any exception is thrown, log it and rethrow - spdlog::debug("RPC error: {}", e.what()); + pimpl->logger.debug("RPC error: {}", e.what()); throw std::system_error(std::make_error_code(std::errc::io_error), "Device already closed or disconnected"); } }); @@ -676,7 +779,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Watchdog thread exception caught: {}", ex.what()); } // Watchdog ended. Useful for checking disconnects @@ -696,7 +799,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional watchdogTimeout * 2) { - spdlog::warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name); + pimpl->logger.warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name); // ping was missed, reset the device watchdogRunning = false; // close the underlying connection @@ -711,6 +814,21 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.debug("Timesync thread exception caught: {}", ex.what()); } timesyncRunning = false; @@ -752,7 +870,7 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.trace("Log vector decoded, size: {}", messages.size()); // log the messages in incremental order (0 -> size-1) for(const auto& msg : messages) { @@ -773,26 +891,53 @@ void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optionallogger.error("Exception while parsing or calling callbacks for log message from device: {}", ex.what()); } } } catch(const std::exception& ex) { // ignore exception from logging - spdlog::debug("Log thread exception caught: {}", ex.what()); + pimpl->logger.debug("Log thread exception caught: {}", ex.what()); } loggingRunning = false; }); - // Below can throw - make sure to gracefully exit threads - try { - auto level = spdlogLevelToLogLevel(spdlog::get_level()); - setLogLevel(level); - setLogOutputLevel(level); + if(utility::getEnv("DEPTHAI_PROFILING") == "1") { + // prepare profiling thread, which will log device messages + profilingThread = std::thread([this]() { + using namespace std::chrono; + try { + ProfilingData lastData = {}; + // TODO(themarpe) - expose + float rate = 1.0f; + while(profilingRunning) { + ProfilingData data = getProfilingData(); + long long w = data.numBytesWritten - lastData.numBytesWritten; + long long r = data.numBytesRead - lastData.numBytesRead; + w /= rate; + r /= rate; + + lastData = data; + + pimpl->logger.debug("Profiling write speed: {:.2f} MiB/s, read speed: {:.2f} MiB/s, total written: {:.2f} MiB, read: {:.2f} MiB", + w / 1024.0f / 1024.0f, + r / 1024.0f / 1024.0f, + data.numBytesWritten / 1024.0f / 1024.0f, + data.numBytesRead / 1024.0f / 1024.0f); + + std::this_thread::sleep_for(duration(1) / rate); + } + } catch(const std::exception& ex) { + // ignore exception from logging + pimpl->logger.debug("Profiling thread exception caught: {}", ex.what()); + } - // Sets system inforation logging rate. By default 1s - setSystemInformationLoggingRate(DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ); + profilingRunning = false; + }); + } + // Below can throw - make sure to gracefully exit threads + try { // Starts and waits for inital timesync setTimesync(DEFAULT_TIMESYNC_PERIOD, DEFAULT_TIMESYNC_NUM_SAMPLES, DEFAULT_TIMESYNC_RANDOM); } catch(const std::exception&) { @@ -925,7 +1070,8 @@ std::string DeviceBase::getDeviceName() { } // 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(), 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 @@ -960,13 +1106,16 @@ std::vector> DeviceBase::getIrDrivers() { return pimpl->rpcClient->call("getIrDrivers"); } -dai::CrashDump DeviceBase::getCrashDump() { - return pimpl->rpcClient->call("getCrashDump").as(); +dai::CrashDump DeviceBase::getCrashDump(bool clearCrashDump) { + return pimpl->rpcClient->call("getCrashDump", clearCrashDump).as(); } bool DeviceBase::hasCrashDump() { - dai::CrashDump crashDump = getCrashDump(); - return !crashDump.crashReports.empty(); + return pimpl->rpcClient->call("hasCrashDump").as(); +} + +ProfilingData DeviceBase::getProfilingData() { + return connection->getProfilingData(); } int DeviceBase::addLogCallback(std::function callback) { @@ -1037,7 +1186,7 @@ void DeviceBase::flashCalibration2(CalibrationHandler calibrationDataHandler) { bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); - spdlog::debug("Flashing calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); + pimpl->logger.debug("Flashing calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); /* if(!calibrationDataHandler.validateCameraArray()) { throw std::runtime_error("Failed to validate the extrinsics connection. Enable debug mode for more information."); @@ -1081,7 +1230,7 @@ void DeviceBase::flashFactoryCalibration(CalibrationHandler calibrationDataHandl bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); - spdlog::debug("Flashing factory calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); + pimpl->logger.debug("Flashing factory calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); if(!factoryPermissions) { throw std::runtime_error("Calling factory API is not allowed in current configuration"); @@ -1156,7 +1305,7 @@ void DeviceBase::flashEepromClear() { bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); - spdlog::debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); + pimpl->logger.debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); if(!protectedPermissions) { throw std::runtime_error("Calling EEPROM clear API is not allowed in current configuration"); @@ -1174,7 +1323,7 @@ void DeviceBase::flashFactoryEepromClear() { bool factoryPermissions = false; bool protectedPermissions = false; getFlashingPermissions(factoryPermissions, protectedPermissions); - spdlog::debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); + pimpl->logger.debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions); if(!protectedPermissions || !factoryPermissions) { throw std::runtime_error("Calling factory EEPROM clear API is not allowed in current configuration"); @@ -1215,11 +1364,11 @@ bool DeviceBase::startPipelineImpl(const Pipeline& pipeline) { pipeline.serialize(schema, assets, assetStorage); // if debug or lower - if(spdlog::get_level() <= spdlog::level::debug) { + if(logger::get_level() <= spdlog::level::debug) { nlohmann::json jSchema = schema; - spdlog::debug("Schema dump: {}", jSchema.dump()); + pimpl->logger.debug("Schema dump: {}", jSchema.dump()); nlohmann::json jAssets = assets; - spdlog::debug("Asset map dump: {}", jAssets.dump()); + pimpl->logger.debug("Asset map dump: {}", jAssets.dump()); } // Load pipelineDesc, assets, and asset storage diff --git a/src/device/DeviceBootloader.cpp b/src/device/DeviceBootloader.cpp index 289060719..ad33db4fd 100644 --- a/src/device/DeviceBootloader.cpp +++ b/src/device/DeviceBootloader.cpp @@ -24,6 +24,7 @@ #include "XLink/XLink.h" #include "spdlog/fmt/chrono.h" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" #include "zlib.h" // Resource compiled assets (cmds) @@ -145,7 +146,7 @@ std::vector DeviceBootloader::createDepthaiApplicationPackage( deviceFirmware = std::move(compressBuffer); auto diff = duration_cast(steady_clock::now() - t1); - spdlog::debug("Compressed firmware for Dephai Application Package. Took {}, size reduced from {:.2f}MiB to {:.2f}MiB", + logger::debug("Compressed firmware for Dephai Application Package. Took {}, size reduced from {:.2f}MiB to {:.2f}MiB", diff, prevSize / (1024.0f * 1024.0f), deviceFirmware.size() / (1024.0f * 1024.0f)); @@ -219,11 +220,11 @@ std::vector DeviceBootloader::createDepthaiApplicationPackage( for(std::size_t i = 0; i < assetStorage.size(); i++) fwPackage[assetStorageSection->offset + i] = assetStorage[i]; // Debug - if(spdlog::get_level() == spdlog::level::debug) { + if(logger::get_level() == spdlog::level::debug) { SBR_SECTION* cur = &sbr.sections[0]; - spdlog::debug("DepthAI Application Package"); + logger::debug("DepthAI Application Package"); for(; cur != lastSection + 1; cur++) { - spdlog::debug("{}, {}B, {}, {}, {}, {}", cur->name, cur->size, cur->offset, cur->checksum, cur->type, cur->flags); + logger::debug("{}, {}B, {}, {}, {}, {}", cur->name, cur->size, cur->offset, cur->checksum, cur->type, cur->flags); } } @@ -284,7 +285,7 @@ void DeviceBootloader::init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl 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()); + logger::debug("Found an actual device by given DeviceInfo: {}", deviceInfo.toString()); } else { throw std::runtime_error("Specified device not found"); } @@ -513,7 +514,7 @@ void DeviceBootloader::init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl // Bump checking thread to not cause spurious warnings/closes std::chrono::milliseconds watchdogTimeout = std::chrono::milliseconds(3000); if(watchdogRunning && std::chrono::steady_clock::now() - prevPingTime > watchdogTimeout * 2) { - spdlog::warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name); + logger::warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name); // ping was missed, reset the device watchdogRunning = false; // close the underlying connection @@ -523,9 +524,9 @@ void DeviceBootloader::init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl }); // Bootloader device ready, check for version - spdlog::debug("Connected bootloader version {}", version.toString()); + logger::debug("Connected bootloader version {}", version.toString()); if(getEmbeddedBootloaderVersion() > version) { - spdlog::info("New bootloader version available. Device has: {}, available: {}", version.toString(), getEmbeddedBootloaderVersion().toString()); + logger::info("New bootloader version available. Device has: {}, available: {}", version.toString(), getEmbeddedBootloaderVersion().toString()); } } @@ -535,7 +536,7 @@ void DeviceBootloader::close() { using namespace std::chrono; auto t1 = steady_clock::now(); - spdlog::debug("DeviceBootloader about to be closed..."); + logger::debug("DeviceBootloader about to be closed..."); // Close connection first; causes Xlink internal calls to unblock semaphore waits and // return error codes, which then allows queues to unblock @@ -556,7 +557,7 @@ void DeviceBootloader::close() { // BUGBUG investigate ownership; can another thread accessing this at the same time? stream = nullptr; - spdlog::debug("DeviceBootloader closed, {}", duration_cast(steady_clock::now() - t1).count()); + logger::debug("DeviceBootloader closed, {}", duration_cast(steady_clock::now() - t1).count()); } // This function is thread-unsafe. The idea of "isClosed" is ephemerial and @@ -663,7 +664,7 @@ DeviceBootloader::ApplicationInfo DeviceBootloader::readApplicationInfo(Memory m DeviceBootloader::MemoryInfo DeviceBootloader::getMemoryInfo(Memory memory) { if(memory == Memory::EMMC && bootloaderType == Type::USB) { // Warn, as result of "no emmc" might be deceiving - spdlog::warn("USB Bootloader type does NOT support eMMC"); + logger::warn("USB Bootloader type does NOT support eMMC"); } // Send request to retrieve bootloader version @@ -787,7 +788,7 @@ std::tuple DeviceBootloader::flashDepthaiApplicationPackage(s try { configJson = readConfigData(); } catch(const std::exception& ex) { - spdlog::debug("Error while trying to read existing bootloader configuration: {}", ex.what()); + logger::debug("Error while trying to read existing bootloader configuration: {}", ex.what()); } // Set the following field 'appMem' (in forward/backward compat manner) configJson["appMem"] = finalAppMem; @@ -796,12 +797,12 @@ std::tuple DeviceBootloader::flashDepthaiApplicationPackage(s std::string errorMsg; std::tie(success, errorMsg) = flashConfigData(configJson); if(success) { - spdlog::debug("Success flashing the appMem configuration to '{}'", static_cast(finalAppMem)); + logger::debug("Success flashing the appMem configuration to '{}'", static_cast(finalAppMem)); } else { throw std::runtime_error(errorMsg); } } catch(const std::exception& ex) { - spdlog::debug("Error while trying to specify final appMem configuration: {}", ex.what()); + logger::debug("Error while trying to specify final appMem configuration: {}", ex.what()); } return ret; @@ -981,7 +982,7 @@ std::tuple DeviceBootloader::flashUserBootloader(std::functio try { configJson = readConfigData(); } catch(const std::exception& ex) { - spdlog::debug("Error while trying to read existing bootloader configuration: {}", ex.what()); + logger::debug("Error while trying to read existing bootloader configuration: {}", ex.what()); } // Set the userBl fields (in forward/backward compat manner) const auto userBlSize = static_cast(package.size()); @@ -993,7 +994,7 @@ std::tuple DeviceBootloader::flashUserBootloader(std::functio std::string errorMsg; std::tie(success, errorMsg) = flashConfigData(configJson); if(success) { - spdlog::debug("Success flashing the configuration userBlSize to '{}' and userBlChecksum to '{}'", userBlSize, userBlChecksum); + logger::debug("Success flashing the configuration userBlSize to '{}' and userBlChecksum to '{}'", userBlSize, userBlChecksum); } else { throw std::runtime_error(errorMsg); } diff --git a/src/device/DeviceLogger.hpp b/src/device/DeviceLogger.hpp index 5a79d74b2..a7da18666 100644 --- a/src/device/DeviceLogger.hpp +++ b/src/device/DeviceLogger.hpp @@ -3,7 +3,7 @@ #include namespace dai { - + class DeviceLogger : public spdlog::logger { using spdlog::logger::logger; @@ -33,7 +33,7 @@ class DeviceLogger : public spdlog::logger { return; } - + // Continue with other fields // logger name log.logger_name = msg.nodeIdName; @@ -46,9 +46,9 @@ class DeviceLogger : public spdlog::logger { log.color_range_end = msg.colorRangeEnd; // actual log message - log.payload = msg.payload; + log.payload = msg.payload; - // Call the internal log_it_ method + // Call the internal log_it_ method log_it_(log, logEnabled, tracebackEnabled); } diff --git a/src/opencv/ImgFrame.cpp b/src/opencv/ImgFrame.cpp index c352d1a13..4e4d16ce2 100644 --- a/src/opencv/ImgFrame.cpp +++ b/src/opencv/ImgFrame.cpp @@ -46,6 +46,9 @@ cv::Mat ImgFrame::getFrame(bool deepCopy) { break; case Type::RAW16: + case Type::RAW14: + case Type::RAW12: + case Type::RAW10: size = cv::Size(getWidth(), getHeight()); type = CV_16UC1; break; @@ -73,7 +76,7 @@ cv::Mat ImgFrame::getFrame(bool deepCopy) { + std::to_string(actualSize) + ". Maybe metadataOnly transfer was made?"); } else if(actualSize > requiredSize) { // FIXME doesn't build on Windows (multiple definitions during link) - // spdlog::warn("ImgFrame has excess data: actual {}, expected {}", actualSize, requiredSize); + // logger::warn("ImgFrame has excess data: actual {}, expected {}", actualSize, requiredSize); } if(getWidth() <= 0 || getHeight() <= 0) { throw std::runtime_error("ImgFrame metadata not valid (width or height = 0)"); @@ -139,6 +142,9 @@ cv::Mat ImgFrame::getCvFrame() { case Type::RAW8: case Type::RAW16: + case Type::RAW14: + case Type::RAW12: + case Type::RAW10: case Type::GRAY8: case Type::GRAYF16: output = frame.clone(); diff --git a/src/openvino/OpenVINO.cpp b/src/openvino/OpenVINO.cpp index 82ab1c340..cd573a5c0 100644 --- a/src/openvino/OpenVINO.cpp +++ b/src/openvino/OpenVINO.cpp @@ -10,6 +10,7 @@ #include "BlobReader.hpp" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" #include "utility/spdlog-fmt.hpp" namespace dai { @@ -151,7 +152,7 @@ bool OpenVINO::areVersionsBlobCompatible(OpenVINO::Version v1, OpenVINO::Version } // If versions weren't matched up in any of the above cases, log an error and return false - spdlog::error("OpenVINO - version compatibility check with invalid values or unknown blob version"); + logger::error("OpenVINO - version compatibility check with invalid values or unknown blob version"); return false; } diff --git a/src/pipeline/datatype/CameraControl.cpp b/src/pipeline/datatype/CameraControl.cpp index 65b969151..8ec645a4f 100644 --- a/src/pipeline/datatype/CameraControl.cpp +++ b/src/pipeline/datatype/CameraControl.cpp @@ -207,4 +207,13 @@ int CameraControl::getLensPosition() const { return cfg.lensPosition; } +dai::RawCameraControl CameraControl::get() const { + return cfg; +} + +CameraControl& CameraControl::set(dai::RawCameraControl config) { + cfg = config; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/EdgeDetectorConfig.cpp b/src/pipeline/datatype/EdgeDetectorConfig.cpp index d26f4258f..2e04f1971 100644 --- a/src/pipeline/datatype/EdgeDetectorConfig.cpp +++ b/src/pipeline/datatype/EdgeDetectorConfig.cpp @@ -19,4 +19,13 @@ EdgeDetectorConfigData EdgeDetectorConfig::getConfigData() const { return cfg.config; } +dai::RawEdgeDetectorConfig EdgeDetectorConfig::get() const { + return cfg; +} + +EdgeDetectorConfig& EdgeDetectorConfig::set(dai::RawEdgeDetectorConfig config) { + cfg = config; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/ImageManipConfig.cpp b/src/pipeline/datatype/ImageManipConfig.cpp index 38c2236ff..f22c40ab0 100644 --- a/src/pipeline/datatype/ImageManipConfig.cpp +++ b/src/pipeline/datatype/ImageManipConfig.cpp @@ -279,4 +279,13 @@ dai::Colormap ImageManipConfig::getColormap() const { return cfg.formatConfig.colormap; } +dai::RawImageManipConfig ImageManipConfig::get() const { + return cfg; +} + +ImageManipConfig& ImageManipConfig::set(dai::RawImageManipConfig config) { + cfg = config; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/SpatialLocationCalculatorConfig.cpp b/src/pipeline/datatype/SpatialLocationCalculatorConfig.cpp index c8fb26132..ce6d50de6 100644 --- a/src/pipeline/datatype/SpatialLocationCalculatorConfig.cpp +++ b/src/pipeline/datatype/SpatialLocationCalculatorConfig.cpp @@ -23,4 +23,13 @@ std::vector SpatialLocationCalculatorConfig return cfg.config; } +dai::RawSpatialLocationCalculatorConfig SpatialLocationCalculatorConfig::get() const { + return cfg; +} + +SpatialLocationCalculatorConfig& SpatialLocationCalculatorConfig::set(dai::RawSpatialLocationCalculatorConfig config) { + cfg = config; + return *this; +} + } // namespace dai diff --git a/src/pipeline/datatype/StreamMessageParser.cpp b/src/pipeline/datatype/StreamMessageParser.cpp index ab320ad25..a000b205d 100644 --- a/src/pipeline/datatype/StreamMessageParser.cpp +++ b/src/pipeline/datatype/StreamMessageParser.cpp @@ -26,6 +26,7 @@ #include "depthai/pipeline/datatype/SpatialLocationCalculatorData.hpp" #include "depthai/pipeline/datatype/StereoDepthConfig.hpp" #include "depthai/pipeline/datatype/SystemInformation.hpp" +#include "depthai/pipeline/datatype/ToFConfig.hpp" #include "depthai/pipeline/datatype/TrackedFeatures.hpp" #include "depthai/pipeline/datatype/Tracklets.hpp" @@ -47,6 +48,7 @@ #include "depthai-shared/datatype/RawSpatialLocations.hpp" #include "depthai-shared/datatype/RawStereoDepthConfig.hpp" #include "depthai-shared/datatype/RawSystemInformation.hpp" +#include "depthai-shared/datatype/RawToFConfig.hpp" #include "depthai-shared/datatype/RawTracklets.hpp" #include "depthai-shared/utility/Serialization.hpp" @@ -72,14 +74,39 @@ inline std::shared_ptr parseDatatype(std::uint8_t* metadata, size_t size, std return tmp; } -std::shared_ptr StreamMessageParser::parseMessage(streamPacketDesc_t* const packet) { +static std::tuple parseHeader(streamPacketDesc_t* const packet) { + if(packet->length < 8) { + throw std::runtime_error("Bad packet, couldn't parse (not enough data)"); + } const int serializedObjectSize = readIntLE(packet->data + packet->length - 4); const auto objectType = static_cast(readIntLE(packet->data + packet->length - 8)); if(serializedObjectSize < 0) { - throw std::runtime_error("Bad packet, couldn't parse"); + throw std::runtime_error("Bad packet, couldn't parse (metadata size negative)"); + } else if(serializedObjectSize > static_cast(packet->length)) { + throw std::runtime_error("Bad packet, couldn't parse (metadata size larger than packet length)"); + } + if(static_cast(packet->length) - 8 - serializedObjectSize < 0) { + throw std::runtime_error("Bad packet, couldn't parse (data too small)"); } const std::uint32_t bufferLength = packet->length - 8 - serializedObjectSize; + if(bufferLength > packet->length) { + throw std::runtime_error("Bad packet, couldn't parse (data too large)"); + } + auto* const metadataStart = packet->data + bufferLength; + + if(metadataStart < packet->data || metadataStart >= packet->data + packet->length) { + throw std::runtime_error("Bad packet, couldn't parse (metadata out of bounds)"); + } + + return {objectType, serializedObjectSize, bufferLength}; +} + +std::shared_ptr StreamMessageParser::parseMessage(streamPacketDesc_t* const packet) { + DatatypeEnum objectType; + size_t serializedObjectSize; + size_t bufferLength; + std::tie(objectType, serializedObjectSize, bufferLength) = parseHeader(packet); auto* const metadataStart = packet->data + bufferLength; // copy data part @@ -162,19 +189,20 @@ std::shared_ptr StreamMessageParser::parseMessage(streamPacketDesc_t* case DatatypeEnum::FeatureTrackerConfig: return parseDatatype(metadataStart, serializedObjectSize, data); break; + + case DatatypeEnum::ToFConfig: + return parseDatatype(metadataStart, serializedObjectSize, data); + break; } throw std::runtime_error("Bad packet, couldn't parse"); } std::shared_ptr StreamMessageParser::parseMessageToADatatype(streamPacketDesc_t* const packet) { - const int serializedObjectSize = readIntLE(packet->data + packet->length - 4); - const auto objectType = static_cast(readIntLE(packet->data + packet->length - 8)); - - if(serializedObjectSize < 0) { - throw std::runtime_error("Bad packet, couldn't parse"); - } - const std::uint32_t bufferLength = packet->length - 8 - serializedObjectSize; + DatatypeEnum objectType; + size_t serializedObjectSize; + size_t bufferLength; + std::tie(objectType, serializedObjectSize, bufferLength) = parseHeader(packet); auto* const metadataStart = packet->data + bufferLength; // copy data part @@ -256,9 +284,13 @@ std::shared_ptr StreamMessageParser::parseMessageToADatatype(streamPa case DatatypeEnum::FeatureTrackerConfig: return std::make_shared(parseDatatype(metadataStart, serializedObjectSize, data)); break; + + case DatatypeEnum::ToFConfig: + return std::make_shared(parseDatatype(metadataStart, serializedObjectSize, data)); + break; } - throw std::runtime_error("Bad packet, couldn't parse"); + throw std::runtime_error("Bad packet, couldn't parse (invalid message type)"); } std::vector StreamMessageParser::serializeMessage(const RawBuffer& data) { diff --git a/src/pipeline/datatype/ToFConfig.cpp b/src/pipeline/datatype/ToFConfig.cpp new file mode 100644 index 000000000..4f8a625be --- /dev/null +++ b/src/pipeline/datatype/ToFConfig.cpp @@ -0,0 +1,41 @@ +#include "depthai/pipeline/datatype/ToFConfig.hpp" + +namespace dai { + +std::shared_ptr ToFConfig::serialize() const { + return raw; +} + +ToFConfig::ToFConfig() : Buffer(std::make_shared()), cfg(*dynamic_cast(raw.get())) {} +ToFConfig::ToFConfig(std::shared_ptr ptr) : Buffer(std::move(ptr)), cfg(*dynamic_cast(raw.get())) {} + +dai::RawToFConfig ToFConfig::get() const { + return cfg; +} + +ToFConfig& ToFConfig::setDepthParams(dai::ToFConfig::DepthParams config) { + cfg.depthParams = config; + return *this; +} + +ToFConfig& ToFConfig::setFreqModUsed(dai::ToFConfig::DepthParams::TypeFMod fmod) { + cfg.depthParams.freqModUsed = fmod; + return *this; +} + +ToFConfig& ToFConfig::setAvgPhaseShuffle(bool enable) { + cfg.depthParams.avgPhaseShuffle = enable; + return *this; +} + +ToFConfig& ToFConfig::set(dai::RawToFConfig config) { + cfg = config; + return *this; +} + +ToFConfig& ToFConfig::setMinAmplitude(float minamp) { + cfg.depthParams.minimumAmplitude = minamp; + return *this; +} + +} // namespace dai diff --git a/src/pipeline/node/Camera.cpp b/src/pipeline/node/Camera.cpp index 06edcb518..6edcc1150 100644 --- a/src/pipeline/node/Camera.cpp +++ b/src/pipeline/node/Camera.cpp @@ -275,5 +275,9 @@ float Camera::getCalibrationAlpha() const { return properties.calibAlpha; } +void Camera::setRawOutputPacked(bool packed) { + properties.rawPacked = packed; +} + } // namespace node } // namespace dai diff --git a/src/pipeline/node/ColorCamera.cpp b/src/pipeline/node/ColorCamera.cpp index 8f8527810..ff021d5ae 100644 --- a/src/pipeline/node/ColorCamera.cpp +++ b/src/pipeline/node/ColorCamera.cpp @@ -54,13 +54,13 @@ void ColorCamera::setCamId(int64_t camId) { // cast to board socket switch(camId) { case 0: - properties.boardSocket = CameraBoardSocket::RGB; + properties.boardSocket = CameraBoardSocket::CAM_A; break; case 1: - properties.boardSocket = CameraBoardSocket::LEFT; + properties.boardSocket = CameraBoardSocket::CAM_B; break; case 2: - properties.boardSocket = CameraBoardSocket::RIGHT; + properties.boardSocket = CameraBoardSocket::CAM_C; break; case 3: properties.boardSocket = CameraBoardSocket::CAM_D; @@ -530,5 +530,9 @@ int ColorCamera::getIspNumFramesPool() { return properties.numFramesPoolIsp; } +void ColorCamera::setRawOutputPacked(bool packed) { + properties.rawPacked = packed; +} + } // namespace node } // namespace dai diff --git a/src/pipeline/node/MonoCamera.cpp b/src/pipeline/node/MonoCamera.cpp index ea979af0a..2a7f44001 100644 --- a/src/pipeline/node/MonoCamera.cpp +++ b/src/pipeline/node/MonoCamera.cpp @@ -46,13 +46,13 @@ void MonoCamera::setCamId(int64_t camId) { // cast to board socket switch(camId) { case 0: - properties.boardSocket = CameraBoardSocket::RGB; + properties.boardSocket = CameraBoardSocket::CAM_A; break; case 1: - properties.boardSocket = CameraBoardSocket::LEFT; + properties.boardSocket = CameraBoardSocket::CAM_B; break; case 2: - properties.boardSocket = CameraBoardSocket::RIGHT; + properties.boardSocket = CameraBoardSocket::CAM_C; break; case 3: properties.boardSocket = CameraBoardSocket::CAM_D; @@ -160,5 +160,9 @@ int MonoCamera::getRawNumFramesPool() const { return properties.numFramesPoolRaw; } +void MonoCamera::setRawOutputPacked(bool packed) { + properties.rawPacked = packed; +} + } // namespace node } // namespace dai diff --git a/src/pipeline/node/StereoDepth.cpp b/src/pipeline/node/StereoDepth.cpp index 91abb5db7..fba8d4e60 100644 --- a/src/pipeline/node/StereoDepth.cpp +++ b/src/pipeline/node/StereoDepth.cpp @@ -4,6 +4,7 @@ #include #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" #include "utility/spdlog-fmt.hpp" namespace dai { @@ -40,7 +41,7 @@ StereoDepth::Properties& StereoDepth::getProperties() { void StereoDepth::setEmptyCalibration(void) { setRectification(false); - spdlog::warn("{} is deprecated. This function call can be replaced by Stereo::setRectification(false). ", __func__); + logger::warn("{} is deprecated. This function call can be replaced by Stereo::setRectification(false). ", __func__); } void StereoDepth::loadMeshData(const std::vector& dataLeft, const std::vector& dataRight) { @@ -138,15 +139,15 @@ void StereoDepth::setRectifyEdgeFillColor(int color) { } void StereoDepth::setRectifyMirrorFrame(bool enable) { (void)enable; - spdlog::warn("{} is deprecated.", __func__); + logger::warn("{} is deprecated.", __func__); } void StereoDepth::setOutputRectified(bool enable) { (void)enable; - spdlog::warn("{} is deprecated. The output is auto-enabled if used", __func__); + logger::warn("{} is deprecated. The output is auto-enabled if used", __func__); } void StereoDepth::setOutputDepth(bool enable) { (void)enable; - spdlog::warn("{} is deprecated. The output is auto-enabled if used", __func__); + logger::warn("{} is deprecated. The output is auto-enabled if used", __func__); } void StereoDepth::setRuntimeModeSwitch(bool enable) { diff --git a/src/pipeline/node/ToF.cpp b/src/pipeline/node/ToF.cpp new file mode 100644 index 000000000..5d25ea75c --- /dev/null +++ b/src/pipeline/node/ToF.cpp @@ -0,0 +1,19 @@ +#include "depthai/pipeline/node/ToF.hpp" + +namespace dai { +namespace node { + +ToF::ToF(const std::shared_ptr& par, int64_t nodeId) : ToF(par, nodeId, std::make_unique()) {} +ToF::ToF(const std::shared_ptr& par, int64_t nodeId, std::unique_ptr props) + : NodeCRTP(par, nodeId, std::move(props)), rawConfig(std::make_shared()), initialConfig(rawConfig) { + setInputRefs({&inputConfig, &input}); + setOutputRefs({&depth, &litude, &error}); +} + +ToF::Properties& ToF::getProperties() { + properties.initialConfig = *rawConfig; + return properties; +} + +} // namespace node +} // namespace dai diff --git a/src/pipeline/node/UVC.cpp b/src/pipeline/node/UVC.cpp new file mode 100644 index 000000000..ed0d165f2 --- /dev/null +++ b/src/pipeline/node/UVC.cpp @@ -0,0 +1,25 @@ +#include "depthai/pipeline/node/UVC.hpp" + +namespace dai { +namespace node { + +UVC::UVC(const std::shared_ptr& par, int64_t nodeId) : UVC(par, nodeId, std::make_unique()) {} +UVC::UVC(const std::shared_ptr& par, int64_t nodeId, std::unique_ptr props) + : NodeCRTP(par, nodeId, std::move(props)) { + setInputRefs(&input); +} + +void UVC::setGpiosOnInit(std::unordered_map list) { + properties.gpioInit = list; +} + +void UVC::setGpiosOnStreamOn(std::unordered_map list) { + properties.gpioStreamOn = list; +} + +void UVC::setGpiosOnStreamOff(std::unordered_map list) { + properties.gpioStreamOff = list; +} + +} // namespace node +} // namespace dai diff --git a/src/pipeline/node/VideoEncoder.cpp b/src/pipeline/node/VideoEncoder.cpp index 5370f2cb1..da8efc018 100644 --- a/src/pipeline/node/VideoEncoder.cpp +++ b/src/pipeline/node/VideoEncoder.cpp @@ -5,6 +5,7 @@ // libraries #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" namespace dai { namespace node { @@ -38,14 +39,14 @@ void VideoEncoder::setProfile(VideoEncoderProperties::Profile profile) { void VideoEncoder::setProfile(std::tuple size, VideoEncoderProperties::Profile profile) { (void)size; - spdlog::warn("VideoEncoder {}: passing 'size' is deprecated. It is auto-determined from first frame", __func__); + logger::warn("VideoEncoder {}: passing 'size' is deprecated. It is auto-determined from first frame", __func__); setProfile(profile); } void VideoEncoder::setProfile(int width, int height, VideoEncoderProperties::Profile profile) { (void)width; (void)height; - spdlog::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); + logger::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); setProfile(profile); } @@ -114,17 +115,17 @@ int VideoEncoder::getQuality() const { } std::tuple VideoEncoder::getSize() const { - spdlog::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); + logger::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); return {0, 0}; } int VideoEncoder::getWidth() const { - spdlog::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); + logger::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); return 0; } int VideoEncoder::getHeight() const { - spdlog::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); + logger::warn("VideoEncoder {} is deprecated. The size is auto-determined from first frame and not known upfront", __func__); return 0; } @@ -162,13 +163,13 @@ void VideoEncoder::setDefaultProfilePreset(float fps, VideoEncoderProperties::Pr void VideoEncoder::setDefaultProfilePreset(int width, int height, float fps, VideoEncoderProperties::Profile profile) { (void)width; (void)height; - spdlog::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); + logger::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); setDefaultProfilePreset(fps, profile); } void VideoEncoder::setDefaultProfilePreset(std::tuple size, float fps, VideoEncoderProperties::Profile profile) { (void)size; - spdlog::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); + logger::warn("VideoEncoder {}: passing 'width'/ 'height' is deprecated. The size is auto-determined from first frame", __func__); setDefaultProfilePreset(fps, profile); } diff --git a/src/utility/Environment.cpp b/src/utility/Environment.cpp index 24ca2fd62..7b0350a32 100644 --- a/src/utility/Environment.cpp +++ b/src/utility/Environment.cpp @@ -6,6 +6,9 @@ #include #include +// project +#include + namespace dai { namespace utility { @@ -13,6 +16,10 @@ static std::mutex mtx; static std::unordered_map map; std::string getEnv(const std::string& var) { + return getEnv(var, Logging::getInstance().logger); +} + +std::string getEnv(const std::string& var, spdlog::logger& logger) { std::unique_lock lock(mtx); if(map.count(var) > 0) { @@ -23,7 +30,7 @@ std::string getEnv(const std::string& var) { // Log if env variable is set if(!value.empty()) { - spdlog::debug("Environment '{}' set to '{}'", var, value); + logger.debug("Environment '{}' set to '{}'", var, value); } return value; diff --git a/src/utility/Environment.hpp b/src/utility/Environment.hpp index 94b582c37..ccf8db7ca 100644 --- a/src/utility/Environment.hpp +++ b/src/utility/Environment.hpp @@ -1,6 +1,7 @@ #pragma once #include +#include namespace dai { @@ -8,6 +9,8 @@ namespace utility { std::string getEnv(const std::string& var); +std::string getEnv(const std::string& var, spdlog::logger& logger); + } // namespace utility } // namespace dai diff --git a/src/utility/Initialization.cpp b/src/utility/Initialization.cpp index 6908c3418..931cb7f5c 100644 --- a/src/utility/Initialization.cpp +++ b/src/utility/Initialization.cpp @@ -6,7 +6,9 @@ // project #include "build/version.hpp" #include "utility/Environment.hpp" +#include "utility/Logging.hpp" #include "utility/Resources.hpp" +#include "utility/XLinkGlobalProfilingLogger.hpp" // libraries #include "XLink/XLink.h" @@ -14,6 +16,7 @@ #include "spdlog/cfg/helpers.h" #include "spdlog/details/os.h" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" extern "C" { #include "XLink/XLinkLog.h" } @@ -61,6 +64,9 @@ bool initialize(std::string additionalInfo, bool installSignalHandler, void* jav bool initialize(const char* additionalInfo, bool installSignalHandler, void* javavm) { // singleton for checking whether depthai was already initialized static const bool initialized = [&]() { + // Initialize logging + Logging::getInstance(); + #ifdef DEPTHAI_ENABLE_BACKWARD // install backward if specified auto envSignalHandler = utility::getEnv("DEPTHAI_INSTALL_SIGNAL_HANDLER"); @@ -71,36 +77,11 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav (void)installSignalHandler; #endif - // Set global logging level from ENV variable 'DEPTHAI_LEVEL' - // Taken from spdlog, to replace with DEPTHAI_LEVEL instead of SPDLOG_LEVEL - // spdlog::cfg::load_env_levels(); - auto envLevel = utility::getEnv("DEPTHAI_LEVEL"); - if(!envLevel.empty()) { - spdlog::cfg::helpers::load_levels(envLevel); - } else { - // Otherwise set default level to WARN - spdlog::set_level(spdlog::level::warn); - } - - auto debugStr = utility::getEnv("DEPTHAI_DEBUG"); - if(!debugStr.empty()) { - // Try parsing the string as a number - try { - int debug{std::stoi(debugStr)}; - if(debug && (spdlog::get_level() > spdlog::level::debug)) { - spdlog::set_level(spdlog::level::debug); - spdlog::info("DEPTHAI_DEBUG enabled, lowered DEPTHAI_LEVEL to 'debug'"); - } - } catch(const std::invalid_argument& e) { - spdlog::warn("DEPTHAI_DEBUG value invalid: {}, should be a number (non-zero to enable)", e.what()); - } - } - // Print core commit and build datetime if(additionalInfo != nullptr && additionalInfo[0] != '\0') { - spdlog::debug("{}", additionalInfo); + logger::debug("{}", additionalInfo); } - spdlog::debug( + logger::debug( "Library information - version: {}, commit: {} from {}, build: {}", build::VERSION, build::COMMIT, build::COMMIT_DATETIME, build::BUILD_DATETIME); // Executed at library load time @@ -120,12 +101,19 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav if(status == X_LINK_INIT_USB_ERROR) { errorMsg += ERROR_MSG_USB_TIP; } - spdlog::debug("Initialize failed - {}", errorMsg); + logger::debug("Initialize failed - {}", errorMsg); throw std::runtime_error(errorMsg); } // Check that USB protocol is available if(!XLinkIsProtocolInitialized(X_LINK_USB_VSC)) { - spdlog::warn("USB protocol not available - {}", ERROR_MSG_USB_TIP); + logger::warn("USB protocol not available - {}", ERROR_MSG_USB_TIP); + } + + // Enable Global XLink profiling + XLinkProfStart(); + auto profilingEnvLevel = utility::getEnv("DEPTHAI_PROFILING"); + if(profilingEnvLevel == "1") { + XLinkGlobalProfilingLogger::getInstance().enable(true); } // TODO(themarpe), move into XLink library @@ -147,7 +135,7 @@ bool initialize(const char* additionalInfo, bool installSignalHandler, void* jav mvLogDefaultLevelSet(MVLOG_FATAL); } - spdlog::debug("Initialize - finished"); + logger::debug("Initialize - finished"); return true; }(); diff --git a/src/utility/Logging.cpp b/src/utility/Logging.cpp new file mode 100644 index 000000000..b9fac2ca6 --- /dev/null +++ b/src/utility/Logging.cpp @@ -0,0 +1,51 @@ +#include "Logging.hpp" + +namespace dai { + +Logging::Logging() : logger("depthai", {std::make_shared()}) { + // Default global logging level set to WARN; override with ENV variable 'DEPTHAI_LEVEL' + // Taken from spdlog, to replace with DEPTHAI_LEVEL instead of SPDLOG_LEVEL + // spdlog::cfg::load_env_levels(); + auto level = spdlog::level::warn; + auto envLevel = utility::getEnv("DEPTHAI_LEVEL", logger); + if(!envLevel.empty()) { + level = parseLevel(envLevel); + } + logger.set_level(level); + + auto debugStr = utility::getEnv("DEPTHAI_DEBUG", logger); + if(!debugStr.empty()) { + // Try parsing the string as a number + try { + int debug{std::stoi(debugStr)}; + if(debug && (level > spdlog::level::debug)) { + logger.set_level(spdlog::level::debug); + logger.info("DEPTHAI_DEBUG enabled, lowered DEPTHAI_LEVEL to 'debug'"); + } + } catch(const std::invalid_argument& e) { + logger.warn("DEPTHAI_DEBUG value invalid: {}, should be a number (non-zero to enable)", e.what()); + } + } +} + +spdlog::level::level_enum Logging::parseLevel(std::string lvl) { + std::transform(lvl.begin(), lvl.end(), lvl.begin(), [](char ch) { return static_cast((ch >= 'A' && ch <= 'Z') ? ch + ('a' - 'A') : ch); }); + + if(lvl == "trace") { + return spdlog::level::trace; + } else if(lvl == "debug") { + return spdlog::level::debug; + } else if(lvl == "info") { + return spdlog::level::info; + } else if(lvl == "warn") { + return spdlog::level::warn; + } else if(lvl == "error") { + return spdlog::level::err; + } else if(lvl == "off") { + return spdlog::level::off; + } else { + throw std::invalid_argument(fmt::format("Cannot parse logging level: {}", lvl)); + } +} + +} // namespace dai diff --git a/src/utility/Logging.hpp b/src/utility/Logging.hpp new file mode 100644 index 000000000..efc721588 --- /dev/null +++ b/src/utility/Logging.hpp @@ -0,0 +1,152 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +// libraries +#include +#include + +// shared +#include + +// project +#include +#include +#include +#include +#include "Environment.hpp" + +namespace dai { + +class Logging { + // private constructor + Logging(); + ~Logging() {} + +public: + static Logging& getInstance() { + static Logging logging; + return logging; + } + Logging(Logging const&) = delete; + void operator=(Logging const&) = delete; + + // Public API + spdlog::logger logger; + spdlog::level::level_enum parseLevel(std::string lvl); +}; + + +namespace logger +{ + +inline spdlog::level::level_enum get_level() +{ + return Logging::getInstance().logger.level(); +} + +template +inline void log(spdlog::source_loc source, spdlog::level::level_enum lvl, const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.log(source, lvl, fmt, std::forward(args)...); +} + +template +inline void log(spdlog::level::level_enum lvl, const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.log(spdlog::source_loc{}, lvl, fmt, std::forward(args)...); +} + +template +inline void trace(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.trace(fmt, std::forward(args)...); +} + +template +inline void debug(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.debug(fmt, std::forward(args)...); +} + +template +inline void info(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.info(fmt, std::forward(args)...); +} + +template +inline void warn(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.warn(fmt, std::forward(args)...); +} + +template +inline void error(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.error(fmt, std::forward(args)...); +} + +template +inline void critical(const FormatString &fmt, Args&&...args) +{ + Logging::getInstance().logger.critical(fmt, std::forward(args)...); +} + +template +inline void log(spdlog::source_loc source, spdlog::level::level_enum lvl, const T &msg) +{ + Logging::getInstance().logger.log(source, lvl, msg); +} + +template +inline void log(spdlog::level::level_enum lvl, const T &msg) +{ + Logging::getInstance().logger.log(lvl, msg); +} + +template +inline void trace(const T &msg) +{ + Logging::getInstance().logger.trace(msg); +} + +template +inline void debug(const T &msg) +{ + Logging::getInstance().logger.debug(msg); +} + +template +inline void info(const T &msg) +{ + Logging::getInstance().logger.info(msg); +} + +template +inline void warn(const T &msg) +{ + Logging::getInstance().logger.warn(msg); +} + +template +inline void error(const T &msg) +{ + Logging::getInstance().logger.error(msg); +} + +template +inline void critical(const T &msg) +{ + Logging::getInstance().logger.critical(msg); +} + +} // namespace logger + + +} // namespace dai diff --git a/src/utility/Resources.cpp b/src/utility/Resources.cpp index 9f8b3d7ea..ec89067cb 100644 --- a/src/utility/Resources.cpp +++ b/src/utility/Resources.cpp @@ -15,6 +15,7 @@ #include "spdlog/details/os.h" #include "spdlog/fmt/chrono.h" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" // shared #include "depthai-shared/device/BoardConfig.hpp" @@ -96,7 +97,7 @@ std::vector Resources::getDeviceFirmware(Device::Config config, da throw std::runtime_error( fmt::format("File at path {}{} doesn't exist.", finalFwBinaryPath, !fwBinaryPath.empty() ? " pointed to by DEPTHAI_DEVICE_BINARY" : "")); } - spdlog::warn("Overriding firmware: {}", finalFwBinaryPath); + logger::warn("Overriding firmware: {}", finalFwBinaryPath); // Read the file and return its contents finalFwBinary = std::vector(std::istreambuf_iterator(stream), {}); } else { @@ -107,7 +108,7 @@ std::vector Resources::getDeviceFirmware(Device::Config config, da {OpenVINO::VERSION_2020_4, OpenVINO::VERSION_2021_1, OpenVINO::VERSION_2021_2, OpenVINO::VERSION_2021_3}); if(deprecatedVersions.count(version)) { - spdlog::warn("OpenVINO {} is deprecated!", OpenVINO::getVersionName(version)); + logger::warn("OpenVINO {} is deprecated!", OpenVINO::getVersionName(version)); } // Main FW @@ -145,7 +146,7 @@ std::vector Resources::getDeviceFirmware(Device::Config config, da // is patching required? if(!depthaiPatch.empty()) { - spdlog::debug("Patching OpenVINO FW version from {} to {}", OpenVINO::getVersionName(MAIN_FW_VERSION), OpenVINO::getVersionName(version)); + logger::debug("Patching OpenVINO FW version from {} to {}", OpenVINO::getVersionName(MAIN_FW_VERSION), OpenVINO::getVersionName(version)); // Load full binary for patch depthaiBinary = resourceMapDevice.at(MAIN_FW_PATH); @@ -220,7 +221,7 @@ std::vector Resources::getBootloaderFirmware(dai::bootloader::Type // TODO(themarpe) - Unify exceptions into meaningful groups throw std::runtime_error(fmt::format("File at path {} pointed to by {} doesn't exist.", blBinaryPath, blEnvVar)); } - spdlog::warn("Overriding bootloader {}: {}", blEnvVar, blBinaryPath); + logger::warn("Overriding bootloader {}: {}", blEnvVar, blBinaryPath); // Read the file and return its content return std::vector(std::istreambuf_iterator(stream), {}); } @@ -330,7 +331,7 @@ std::function getLazyTarXzFunction(MTX& mtx, CV& cv, BOOL& ready, PATH c auto t3 = steady_clock::now(); // Debug - logs loading times - spdlog::debug( + logger::debug( "Resources - Archive '{}' open: {}, archive read: {}", cmrcPath, duration_cast(t2 - t1), duration_cast(t3 - t2)); // Notify that that preload is finished diff --git a/src/utility/XLinkGlobalProfilingLogger.cpp b/src/utility/XLinkGlobalProfilingLogger.cpp new file mode 100644 index 000000000..7de1de442 --- /dev/null +++ b/src/utility/XLinkGlobalProfilingLogger.cpp @@ -0,0 +1,61 @@ +#include "utility/XLinkGlobalProfilingLogger.hpp" + +#include + +#include "Logging.hpp" +#include "depthai/utility/Initialization.hpp" + +using namespace std; +using namespace std::chrono; + +namespace dai { + +XLinkGlobalProfilingLogger::XLinkGlobalProfilingLogger() {} + +void XLinkGlobalProfilingLogger::enable(bool en) { + running = false; + if(thr.joinable()) thr.join(); + + if(en) { + running = true; + XLinkProfStart(); + thr = std::thread([this]() { + XLinkProf_t lastProf = {}; + while(running) { + XLinkProf_t prof; + XLinkGetGlobalProfilingData(&prof); + + long long w = prof.totalWriteBytes - lastProf.totalWriteBytes; + long long r = prof.totalReadBytes - lastProf.totalReadBytes; + w /= rate.load(); + r /= rate.load(); + + logger::debug("Profiling global write speed: {:.2f} MiB/s, read speed: {:.2f} MiB/s, total written: {:.2f} MiB, read: {:.2f} MiB", + w / 1024.0f / 1024.0f, + r / 1024.0f / 1024.0f, + prof.totalWriteBytes / 1024.0f / 1024.0f, + prof.totalReadBytes / 1024.0f / 1024.0f); + + lastProf = prof; + this_thread::sleep_for(duration(1) / rate.load()); + } + }); + } +} +void XLinkGlobalProfilingLogger::setRate(float rate) { + this->rate = rate; +} + +float XLinkGlobalProfilingLogger::getRate() { + return rate; +} +XLinkGlobalProfilingLogger::~XLinkGlobalProfilingLogger() { + enable(false); +} + +XLinkGlobalProfilingLogger& XLinkGlobalProfilingLogger::getInstance() { + static XLinkGlobalProfilingLogger instance; // Guaranteed to be destroyed, instantiated on first use. + return instance; +} + +} // namespace dai diff --git a/src/utility/XLinkGlobalProfilingLogger.hpp b/src/utility/XLinkGlobalProfilingLogger.hpp new file mode 100644 index 000000000..f608d8617 --- /dev/null +++ b/src/utility/XLinkGlobalProfilingLogger.hpp @@ -0,0 +1,38 @@ + +#pragma once + +#include +#include +#include +#include +#include +#include + +// project +#include +#include +#include +#include + +namespace dai { + +class XLinkGlobalProfilingLogger { + // private constructor + XLinkGlobalProfilingLogger(); + ~XLinkGlobalProfilingLogger(); + + std::atomic running{false}; + std::atomic rate{1.0f}; + std::thread thr; + +public: + static XLinkGlobalProfilingLogger& getInstance(); + XLinkGlobalProfilingLogger(XLinkGlobalProfilingLogger const&) = delete; + void operator=(XLinkGlobalProfilingLogger const&) = delete; + + void enable(bool enable); + void setRate(float hz); + float getRate(); +}; + +} // namespace dai diff --git a/src/xlink/XLinkConnection.cpp b/src/xlink/XLinkConnection.cpp index a025daa87..3e41fac1d 100644 --- a/src/xlink/XLinkConnection.cpp +++ b/src/xlink/XLinkConnection.cpp @@ -23,6 +23,7 @@ extern "C" { #include "spdlog/details/os.h" #include "spdlog/fmt/chrono.h" #include "spdlog/spdlog.h" +#include "utility/Logging.hpp" namespace dai { @@ -98,7 +99,7 @@ static XLinkProtocol_t getDefaultProtocol() { } else if(protocolStr == "tcpip") { defaultProtocol = X_LINK_TCP_IP; } else { - spdlog::warn("Unsupported protocol specified"); + logger::warn("Unsupported protocol specified"); } return defaultProtocol; @@ -121,7 +122,9 @@ std::vector XLinkConnection::getAllConnectedDevices(XLinkDeviceState suitableDevice.platform = X_LINK_ANY_PLATFORM; suitableDevice.state = state; - auto allowedDeviceIds = utility::getEnv("DEPTHAI_DEVICE_MXID_LIST"); + auto allowedDeviceMxIds = utility::getEnv("DEPTHAI_DEVICE_MXID_LIST"); + auto allowedDeviceIds = utility::getEnv("DEPTHAI_DEVICE_ID_LIST"); + auto allowedDeviceNames = utility::getEnv("DEPTHAI_DEVICE_NAME_LIST"); auto status = XLinkFindAllSuitableDevices(suitableDevice, deviceDescAll.data(), static_cast(deviceDescAll.size()), &numdev); if(status != X_LINK_SUCCESS) throw std::runtime_error("Couldn't retrieve all connected devices"); @@ -133,18 +136,20 @@ std::vector XLinkConnection::getAllConnectedDevices(XLinkDeviceState if(info.status == X_LINK_SUCCESS) { // device is okay } else if(info.status == X_LINK_INSUFFICIENT_PERMISSIONS) { - spdlog::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", + logger::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", XLinkDeviceStateToStr(info.state), info.name); continue; } else { - spdlog::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(info.state), info.name); + logger::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(info.state), info.name); continue; } } + bool allowedMxId = allowedDeviceMxIds.find(info.getMxId()) != std::string::npos || allowedDeviceMxIds.empty(); bool allowedId = allowedDeviceIds.find(info.getMxId()) != std::string::npos || allowedDeviceIds.empty(); - if(allowedId) { + bool allowedName = allowedDeviceNames.find(info.name) != std::string::npos || allowedDeviceNames.empty(); + if(allowedMxId && allowedId && allowedName) { devices.push_back(info); } } @@ -169,12 +174,12 @@ std::tuple XLinkConnection::getFirstDevice(XLinkDeviceState_t if(desc.status == X_LINK_SUCCESS) { // device is okay } else if(desc.status == X_LINK_INSUFFICIENT_PERMISSIONS) { - spdlog::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", + logger::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", XLinkDeviceStateToStr(desc.state), desc.name); return {false, {}}; } else { - spdlog::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(desc.state), desc.name); + logger::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(desc.state), desc.name); return {false, {}}; } } @@ -198,12 +203,12 @@ std::tuple XLinkConnection::getDeviceByMxId(std::string mxId, if(desc.status == X_LINK_SUCCESS) { // device is okay } else if(desc.status == X_LINK_INSUFFICIENT_PERMISSIONS) { - spdlog::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", + logger::warn("Insufficient permissions to communicate with {} device having name \"{}\". Make sure udev rules are set", XLinkDeviceStateToStr(desc.state), desc.name); return {false, {}}; } else { - spdlog::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(desc.state), desc.name); + logger::warn("skipping {} device having name \"{}\"", XLinkDeviceStateToStr(desc.state), desc.name); return {false, {}}; } } @@ -255,9 +260,9 @@ DeviceInfo XLinkConnection::bootBootloader(const DeviceInfo& deviceInfo) { std::chrono::milliseconds value{std::stoi(valstr)}; *ev.second = value; // auto initial = *ev.second; - // spdlog::warn("{} override: {} -> {}", name, initial, value); + // logger::warn("{} override: {} -> {}", name, initial, value); } catch(const std::invalid_argument& e) { - spdlog::warn("{} value invalid: {}", name, e.what()); + logger::warn("{} value invalid: {}", name, e.what()); } } } @@ -319,7 +324,7 @@ void XLinkConnection::close() { auto ret = XLinkResetRemoteTimeout(deviceLinkId, duration_cast(RESET_TIMEOUT).count()); if(ret != X_LINK_SUCCESS) { - spdlog::debug("XLinkResetRemoteTimeout returned: {}", XLinkErrorToStr(ret)); + logger::debug("XLinkResetRemoteTimeout returned: {}", XLinkErrorToStr(ret)); } deviceLinkId = -1; @@ -342,7 +347,7 @@ void XLinkConnection::close() { } while(!found && steady_clock::now() - t1 < BOOTUP_SEARCH); } - spdlog::debug("XLinkResetRemote of linkId: ({})", previousLinkId); + logger::debug("XLinkResetRemote of linkId: ({})", previousLinkId); } closed = true; @@ -402,7 +407,7 @@ void XLinkConnection::initDevice(const DeviceInfo& deviceToInit, XLinkDeviceStat *ev.second = value; // auto initial = *ev.second; } catch(const std::invalid_argument& e) { - spdlog::warn("{} value invalid: {}", name, e.what()); + logger::warn("{} value invalid: {}", name, e.what()); } } } @@ -452,7 +457,7 @@ void XLinkConnection::initDevice(const DeviceInfo& deviceToInit, XLinkDeviceStat // Use "name" as hint only, but might still change bootedDescInfo.nameHintOnly = true; - spdlog::debug("Searching for booted device: {}, name used as hint only", bootedDeviceInfo.toString()); + logger::debug("Searching for booted device: {}, name used as hint only", bootedDeviceInfo.toString()); // Find booted device deviceDesc_t foundDeviceDesc = {}; @@ -499,4 +504,26 @@ std::string XLinkConnection::convertErrorCodeToString(XLinkError_t errorCode) { return XLinkErrorToStr(errorCode); } +ProfilingData XLinkConnection::getGlobalProfilingData() { + ProfilingData data; + XLinkProf_t prof; + if(XLinkGetGlobalProfilingData(&prof) != X_LINK_SUCCESS) { + throw std::runtime_error("Couldn't retrieve profiling data"); + } + data.numBytesRead = prof.totalReadBytes; + data.numBytesWritten = prof.totalWriteBytes; + return data; +} + +ProfilingData XLinkConnection::getProfilingData() { + ProfilingData data; + XLinkProf_t prof; + if(XLinkGetProfilingData(deviceLinkId, &prof) != X_LINK_SUCCESS) { + throw std::runtime_error("Couldn't retrieve profiling data"); + } + data.numBytesRead = prof.totalReadBytes; + data.numBytesWritten = prof.totalWriteBytes; + return data; +} + } // namespace dai diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index a1acf6903..21260e2f8 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -269,3 +269,6 @@ target_compile_definitions(stability_stress_test PRIVATE BLOB_PATH="${tiny_yolo_ # add_test(stability_stress_test_poe stability_stress_test) # set_tests_properties(stability_stress_test PROPERTIES ENVIRONMENT "UBSAN_OPTIONS=halt_on_error=1;DEPTHAI_PROTOCOL=usb" LABELS stability_usb) # set_tests_properties(stability_stress_test_poe PROPERTIES ENVIRONMENT "UBSAN_OPTIONS=halt_on_error=1;DEPTHAI_PROTOCOL=poe" LABELS stability_poe) + +# StreamMessageParser tests +dai_add_test(stream_message_parser_test src/stream_message_parser_test.cpp) diff --git a/tests/src/multiple_devices_test.cpp b/tests/src/multiple_devices_test.cpp index e76af33f6..d65dcae65 100644 --- a/tests/src/multiple_devices_test.cpp +++ b/tests/src/multiple_devices_test.cpp @@ -41,7 +41,7 @@ int main() { // Properties camRgb->setPreviewSize(300, 300); - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P); camRgb->setInterleaved(false); camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::RGB); diff --git a/tests/src/pipeline_test.cpp b/tests/src/pipeline_test.cpp index 5cc9ae310..26e394d28 100644 --- a/tests/src/pipeline_test.cpp +++ b/tests/src/pipeline_test.cpp @@ -57,3 +57,27 @@ TEST_CASE("Cross pipeline link with Input and Output") { // Then check that actually linking throws REQUIRE_THROWS(xin->out.link(xout->input)); } + +TEST_CASE("Duplicate xlink stream names") { + dai::Pipeline p; + auto sysInfo1 = p.create(); + auto sysInfo2 = p.create(); + auto xout1 = p.create(); + auto xout2 = p.create(); + sysInfo1->out.link(xout1->input); + sysInfo2->out.link(xout2->input); + xout1->setStreamName("test1"); + xout2->setStreamName("test1"); + REQUIRE_THROWS_AS(dai::Device{p}, std::invalid_argument); + + p = {}; + auto script1 = p.create(); + auto script2 = p.create(); + auto xin1 = p.create(); + auto xin2 = p.create(); + xin1->out.link(script1->inputs["in"]); + xin2->out.link(script2->inputs["in"]); + xin1->setStreamName("test2"); + xin1->setStreamName("test2"); + REQUIRE_THROWS_AS(dai::Device{p}, std::invalid_argument); +} diff --git a/tests/src/stability_stress_test.cpp b/tests/src/stability_stress_test.cpp index e784c80d5..5add1282b 100644 --- a/tests/src/stability_stress_test.cpp +++ b/tests/src/stability_stress_test.cpp @@ -133,18 +133,18 @@ int main(int argc, char** argv) { // xoutTrackedFeaturesRight->setStreamName("trackedFeaturesRight"); // Properties - camRgb->setBoardSocket(dai::CameraBoardSocket::RGB); + camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A); camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_4_K); camRgb->setPreviewSize(416, 416); camRgb->setInterleaved(false); camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); camRgb->setFps(RGB_FPS); - monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); + monoLeft->setCamera("left"); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); monoLeft->setFps(MONO_FPS); - monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); + monoRight->setCamera("right"); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); monoRight->setFps(MONO_FPS); @@ -155,7 +155,7 @@ int main(int argc, char** argv) { stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // Align depth map to the perspective of RGB camera, on which inference is done - stereo->setDepthAlign(dai::CameraBoardSocket::RGB); + stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A); stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight()); spatialDetectionNetwork->setBlobPath(nnPath); diff --git a/tests/src/stream_message_parser_test.cpp b/tests/src/stream_message_parser_test.cpp new file mode 100644 index 000000000..07ef8839b --- /dev/null +++ b/tests/src/stream_message_parser_test.cpp @@ -0,0 +1,131 @@ +#include + +// Include depthai library +#include +#include + +// TODO(themarpe) - fuzz me instead + +TEST_CASE("Correct message") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + auto des = dai::StreamMessageParser::parseMessageToADatatype(&packet); + auto ser2 = dai::StreamMessageParser::serializeMessage(des); + + REQUIRE(ser == ser2); +} + +TEST_CASE("Incorrect message bad size") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + // wreak havoc on serialized data + ser[ser.size() - 1] = 100; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessageToADatatype(&packet)); +} + +TEST_CASE("Incorrect message negative size") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + // wreak havoc on serialized data + ser[ser.size() - 1] = 200; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessageToADatatype(&packet)); +} + +TEST_CASE("Incorrect message too small size") { + std::vector ser = {0, 1, 2}; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessageToADatatype(&packet)); +} + +TEST_CASE("Incorrect message too small size 2") { + std::vector ser = {0, 1, 1}; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessageToADatatype(&packet)); +} + +TEST_CASE("Raw - Correct message") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + auto des = dai::StreamMessageParser::parseMessage(&packet); + auto ser2 = dai::StreamMessageParser::serializeMessage(des); + + REQUIRE(ser == ser2); +} + +TEST_CASE("Raw - Incorrect message bad size") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + // wreak havoc on serialized data + ser[ser.size() - 1] = 100; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessage(&packet)); +} + +TEST_CASE("Raw - Incorrect message negative size") { + dai::ImgFrame frm; + auto ser = dai::StreamMessageParser::serializeMessage(frm); + + // wreak havoc on serialized data + ser[ser.size() - 1] = 200; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessage(&packet)); +} + +TEST_CASE("Raw - Incorrect message too small size") { + std::vector ser = {0, 1, 2}; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessage(&packet)); +} + +TEST_CASE("Raw - Incorrect message too small size 2") { + std::vector ser = {0, 1, 1}; + + streamPacketDesc_t packet; + packet.data = ser.data(); + packet.length = ser.size(); + + REQUIRE_THROWS(dai::StreamMessageParser::parseMessage(&packet)); +} \ No newline at end of file