diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 110309239..7af8d8014 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package depthai ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2.19.1 (2022-11-28) +----------- +* Added Device getDeviceName API +* OAK-FFC 4P (R5M1E5) IR/Dot support +* Additional Stability bugfixes to go along with 2.19.0 for PoE devices +* Protected productName field in EEPROM +* Contributors: Alex Bougdan, Szabolcs Gergely, Martin Peterlin + 2.19.0 (2022-09-20) ----------- diff --git a/CMakeLists.txt b/CMakeLists.txt index db6f05b01..6313640c6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -43,7 +43,7 @@ if(WIN32) endif() # Create depthai project -project(depthai VERSION "2.19.0" LANGUAGES CXX C) +project(depthai VERSION "2.19.1" LANGUAGES CXX C) get_directory_property(has_parent PARENT_DIRECTORY) if(has_parent) set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE) diff --git a/cmake/Depthai/DepthaiDeviceSideConfig.cmake b/cmake/Depthai/DepthaiDeviceSideConfig.cmake index 04f6ccfa9..2ac14a94b 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 "b3aeaf23ff5857fc8f79d412ceefc08da23e7aad") +set(DEPTHAI_DEVICE_SIDE_COMMIT "adbcc016c8bd5a5580a26d8b6250f77160203666") # "version if applicable" set(DEPTHAI_DEVICE_SIDE_VERSION "") diff --git a/examples/ColorCamera/rgb_preview.cpp b/examples/ColorCamera/rgb_preview.cpp index 67deae9cc..b078a0cc3 100644 --- a/examples/ColorCamera/rgb_preview.cpp +++ b/examples/ColorCamera/rgb_preview.cpp @@ -41,6 +41,9 @@ int main() { cout << "Bootloader version: " << device.getBootloaderVersion()->toString() << endl; } + // Device name + cout << "Device name: " << device.getDeviceName() << endl; + // Output queue will be used to get the rgb frames from the output defined above auto qRgb = device.getOutputQueue("rgb", 4, false); diff --git a/include/depthai/device/CalibrationHandler.hpp b/include/depthai/device/CalibrationHandler.hpp index 29ab3b6aa..aeb17a659 100644 --- a/include/depthai/device/CalibrationHandler.hpp +++ b/include/depthai/device/CalibrationHandler.hpp @@ -19,6 +19,7 @@ namespace dai { * - batchName * - batchTime * - boardOptions + * - productName */ class CalibrationHandler { public: diff --git a/include/depthai/device/DeviceBase.hpp b/include/depthai/device/DeviceBase.hpp index de6bce7bc..4e62fa077 100644 --- a/include/depthai/device/DeviceBase.hpp +++ b/include/depthai/device/DeviceBase.hpp @@ -373,6 +373,12 @@ class DeviceBase { */ DeviceInfo getDeviceInfo() const; + /** + * Get device name if available + * @returns device name or empty string if not available + */ + std::string getDeviceName(); + /** * Get MxId of device * diff --git a/package.xml b/package.xml index cbc1e585a..7a1126f6e 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ depthai - 2.19.0 + 2.19.1 DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform Sachin Guruswamy diff --git a/src/device/DeviceBase.cpp b/src/device/DeviceBase.cpp index 94311f782..21cb7bff4 100644 --- a/src/device/DeviceBase.cpp +++ b/src/device/DeviceBase.cpp @@ -892,6 +892,34 @@ DeviceInfo DeviceBase::getDeviceInfo() const { return deviceInfo; } +std::string DeviceBase::getDeviceName() { + checkClosed(); + + std::string deviceName; + EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData(); + if((deviceName = eeprom.productName).empty()) { + eeprom = readCalibrationOrDefault().getEepromData(); + if((deviceName = eeprom.productName).empty()) { + deviceName = eeprom.boardName; + } + } + + // Convert to device naming from display/product naming + std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun(std::toupper)); + std::replace(deviceName.begin(), deviceName.end(), ' ', '-'); + + // Handle some known legacy cases + if(deviceName == "BW1098OBC") { + deviceName = "OAK-D"; + } else if(deviceName == "DM2097") { + deviceName = "OAK-D-CM4-POE"; + } else if(deviceName == "BW1097") { + deviceName = "OAK-D-CM3"; + } + + return deviceName; +} + void DeviceBase::setLogOutputLevel(LogLevel level) { checkClosed(); diff --git a/tests/src/stability_stress_test.cpp b/tests/src/stability_stress_test.cpp index 2d8099baf..e784c80d5 100644 --- a/tests/src/stability_stress_test.cpp +++ b/tests/src/stability_stress_test.cpp @@ -13,6 +13,24 @@ #include #endif +static constexpr int RGB_FPS = 20; +static constexpr int MONO_FPS = 20; +static constexpr int ENCODER_FPS = 10; + +void printSystemInformation(dai::SystemInformation info) { + printf("Ddr used / total - %.2f / %.2f MiB\n", info.ddrMemoryUsage.used / (1024.0f * 1024.0f), info.ddrMemoryUsage.total / (1024.0f * 1024.0f)); + printf("Cmx used / total - %.2f / %.2f MiB\n", info.cmxMemoryUsage.used / (1024.0f * 1024.0f), info.cmxMemoryUsage.total / (1024.0f * 1024.0f)); + printf("LeonCss heap used / total - %.2f / %.2f MiB\n", + info.leonCssMemoryUsage.used / (1024.0f * 1024.0f), + info.leonCssMemoryUsage.total / (1024.0f * 1024.0f)); + printf("LeonMss heap used / total - %.2f / %.2f MiB\n", + info.leonMssMemoryUsage.used / (1024.0f * 1024.0f), + info.leonMssMemoryUsage.total / (1024.0f * 1024.0f)); + const auto& t = info.chipTemperature; + printf("Chip temperature - average: %.2f, css: %.2f, mss: %.2f, upa: %.2f, dss: %.2f\n", t.average, t.css, t.mss, t.upa, t.dss); + printf("Cpu usage - Leon CSS: %.2f %%, Leon MSS: %.2f %%\n", info.leonCssCpuUsage.average * 100, info.leonMssCpuUsage.average * 100); +} + static const std::vector labelMap = { "person", "bicycle", "car", "motorbike", "aeroplane", "bus", "train", "truck", "boat", "traffic light", "fire hydrant", "stop sign", "parking meter", "bench", "bird", "cat", "dog", "horse", @@ -63,6 +81,7 @@ int main(int argc, char** argv) { auto edgeDetectorLeft = pipeline.create(); auto edgeDetectorRight = pipeline.create(); auto edgeDetectorRgb = pipeline.create(); + auto sysLog = pipeline.create(); #ifdef DEPTHAI_STABILITY_TEST_SCRIPT auto script1 = pipeline.create(); auto script2 = pipeline.create(); @@ -84,6 +103,7 @@ int main(int argc, char** argv) { auto xoutEdgeLeft = pipeline.create(); auto xoutEdgeRight = pipeline.create(); auto xoutEdgeRgb = pipeline.create(); + auto xoutSysLog = pipeline.create(); #ifdef DEPTHAI_STABILITY_TEST_SCRIPT auto scriptOut = pipeline.create(); auto scriptOut2 = pipeline.create(); @@ -97,6 +117,7 @@ int main(int argc, char** argv) { xoutDepth->setStreamName("depth"); xoutNN->setStreamName("detections"); xoutRgb->setStreamName("rgb"); + xoutSysLog->setStreamName("sysinfo"); const auto edgeLeftStr = "edge left"; const auto edgeRightStr = "edge right"; const auto edgeRgbStr = "edge rgb"; @@ -117,17 +138,20 @@ int main(int argc, char** argv) { camRgb->setPreviewSize(416, 416); camRgb->setInterleaved(false); camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR); + camRgb->setFps(RGB_FPS); monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT); monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + monoLeft->setFps(MONO_FPS); monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT); monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P); + monoRight->setFps(MONO_FPS); // Setting to 26fps will trigger error - ve1->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H264_MAIN); - ve2->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H265_MAIN); - ve3->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H264_MAIN); + ve1->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H264_MAIN); + ve2->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H265_MAIN); + ve3->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H264_MAIN); stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY); // Align depth map to the perspective of RGB camera, on which inference is done @@ -150,6 +174,8 @@ int main(int argc, char** argv) { edgeDetectorRgb->setMaxOutputFrameSize(8294400); + sysLog->setRate(0.2f); + #ifdef DEPTHAI_STABILITY_TEST_SCRIPT std::string source1 = R"( import time @@ -250,6 +276,9 @@ int main(int argc, char** argv) { camRgb->video.link(edgeDetectorRgb->inputImage); edgeDetectorLeft->outputImage.link(xoutEdgeLeft->input); edgeDetectorRight->outputImage.link(xoutEdgeRight->input); + sysLog->out.link(xoutSysLog->input); + xoutSysLog->input.setBlocking(false); + xoutSysLog->input.setQueueSize(1); #ifdef DEPTHAI_STABILITY_TEST_SCRIPT script1->outputs["out"].link(script2->inputs["in"]); @@ -269,6 +298,8 @@ int main(int argc, char** argv) { // Connect to device and start pipeline dai::Device device(pipeline); + auto usb_speed = device.getUsbSpeed(); + // Output queues will be used to get the encoded data from the output defined above auto outQ1 = device.getOutputQueue("ve1Out", 30, false); auto outQ2 = device.getOutputQueue("ve2Out", 30, false); @@ -279,7 +310,7 @@ int main(int argc, char** argv) { auto edgeLeftQueue = device.getOutputQueue(edgeLeftStr, 8, false); auto edgeRightQueue = device.getOutputQueue(edgeRightStr, 8, false); auto edgeRgbQueue = device.getOutputQueue(edgeRgbStr, 8, false); - + auto qSysInfo = device.getOutputQueue("sysinfo", 4, false); #ifdef DEPTHAI_STABILITY_TEST_SCRIPT auto scriptQueue = device.getOutputQueue("script", 8, false); auto script2Queue = device.getOutputQueue("script2", 8, false); @@ -298,7 +329,7 @@ int main(int argc, char** argv) { mutex countersMtx; unordered_map counters; - thread countingThread([&countersMtx, &counters, &device, TEST_TIMEOUT]() { + thread countingThread([&countersMtx, &counters, &device, &usb_speed, TEST_TIMEOUT]() { // Initial delay this_thread::sleep_for(5s); @@ -310,6 +341,7 @@ int main(int argc, char** argv) { bool failed = counters.size() == 0; cout << "[" << duration_cast(steady_clock::now() - timeoutStopwatch).count() << "s] " + << "Usb speed " << usb_speed << " " << "FPS: "; for(const auto& kv : counters) { if(kv.second == 0) { @@ -353,6 +385,13 @@ int main(int argc, char** argv) { auto edgeLefts = edgeLeftQueue->tryGetAll(); auto edgeRights = edgeRightQueue->tryGetAll(); + auto sysInfo = qSysInfo->tryGet(); + if(sysInfo) { + printf("----------------------------------------\n"); + std::cout << "Usb speed: " << usb_speed << std::endl; + printSystemInformation(*sysInfo); + printf("----------------------------------------\n"); + } #ifdef DEPTHAI_STABILITY_TEST_SCRIPT auto script = scriptQueue->tryGetAll(); auto script2 = script2Queue->tryGetAll();