Skip to content

Commit 46de84b

Browse files
saching13alex-luxonisthemarpeSzabolcsGergelySzabolcsGergely
authored
Ros release 2.19.1 (#649)
* Update FW: allow OV9282/OV9782 on RGB socket TODO: ColorISP * Color/MonoCamera: add extra resolutions for OV9782 and OV7251 support * Update FW: initial ColorCamera support for OV9782 * Update FW: improve OV9782 colors * Update FW: OV9782 on RGB socket, working with OV9282 on L/R * Update FW: fix OV9782 bayer order * Update FW: improve OV9782 color saturation and sharpness * TMP: OV9782(color) working on Left and/or Right sockets * Update FW: initial support for LUX-D-LITE: IMX214 and OV7251 * Update FW: fix some OV7251 flickering, change stereo res to 480p, improve IMX214 focusing * Update FW: improved focus for IMX214, lowered range * CameraControl: add `setExternalTrigger(numFramesBurst)` * ImgFrame: add API to get camera settings: getLensPosition(), getExposureTime(), getSensitivity() Only the first is implemented for now * setManualFocus auto-handles focus mode now, don't set * Update FW: report exposure + iso too in ImgFrame for RGB, (note: lens position may be reported one frame in advance), fix black image when initial manual exposure was set with other controls, fix switching from auto to manual exposure causing the lens to jump to zero (note: the lens is directly set now with manual focus, bypassing 3A) * CameraControl setExternalTrigger: add numFramesDiscard param * CameraControl: add `setManualWhiteBalance(colorTemperatureK)` * Update FW: reduce ColorCamera still pool: 4 -> 1 frame * Update FW: support for up to 3x IMX378/IMX477 or 3x OV9782 color cameras. Note: configs for Left and Right sockets must be identical for now * Fix FW, support for multiple IMX378/477 * Update FW (IMX214 multiple resolutions), add more camera sockets * Update FW: CAM-D (4th socket) tested, AR0234 support. Note: if AR0234 sensors are used, cannot be combined with other types at the moment (due to tuning blobs in use) * Update FW: changes for IMX214/OV7251, other fixes * Update FW: fix ColorCamera `preview`/`video`/`still` when multiple cameras use these outputs * Update FW: change SIPP mem alloc to allow 4x ColorCamera to operate at the same time * Update FW: StereoDepth: fix RGB alignment when running at calib resolution (OAK-D with 800_P or OAK-D-Lite) * Update FW: fix for IMX378 still output at 12MP * Update FW: OV9282/9782 img orientation per camera, fix sync mode * Update FW: - support for camera modules with IMX380 sensor id, reusing IMX378 driver (some Arducam IMX577(?)) - soft-reset the sensor before config, to fix streaming with some Arducam modules * Update FW: IMX577 proper support (0577 sensor ID) * CameraControl: add setAutoFocusLensRange * Add `CameraControl::setFrameSyncMode`, controlling the FSIN pin I/O and camera sync behavior. Implemented for OV9282/OV9782 for now. Note: if one camera sets it to OUTPUT, and other(s) to INPUT, the hardware sync will work, but currently there's one frame de-sync in the sequence numbers (first frame is lost from the 'slave' cameras). This will be fixed * changed spdlog visibility * Add Device::getConnectedCameraProperties * Add new predefined resolutions for ColorCamera: THE_1200_P, THE_13_MP * Update FW: configurable FPS and fix enumeration issues with AR0234 * Added some getters to CameraControl and modified to use chrono where possible * Update FW: populate `CameraProperties::hasAutofocus` * OV5645 and 5MP resolution support * Update FW: fixes for multiple IMX378/477 * Update FW: fixes for OV9282/9782 on CAM-D, fix stereo rectified frame type for color * Update FW: allow `StereoDepth` to work with `ColorCamera`s, without having to call `StereoDepth::setInputResolution` * Add dot-projector/flood-illuminator brightness control for OAK-D-Pro-W, fix OV9782 slow AE due to missing AF * Allow using AR0234/OV5645 (but at degraded image quality) with other sensors enabled at the same time * Update FW with multiple fixes: - properly handle manual/auto focus with multiple cameras - fix potential init failure with same sensors (IMX378/477/214 / AR0234 / OV5645) on Left and Right sockets - fix sensor name reporting for AR0234 / IMX378/380/477/577 * Fix CI build (not matching bootloader-shared commits) * Script: add optional name parameter to `setScriptPath`, might come handy if the path is long, to have a shorter identifier * ColorCamera/MonoCamera: add `frameEvent` output, to be used for IR control, etc. * Update FW: FSYNC for IMX378 * Update FW, add initial support for IMX582/IMX586 * Updates for IMX582 - full 48MP res, temporarily center cropped (5312x6000 out of 8000x6000) * CameraControl: add STROBE MX-GPIO control, applicable for ext trig mode. AR0234 ext trig: - `cam[c].initialControl.setExternalTrigger(1, 0)` for snapshot mode (exposure+readout following immediately after trigger) - `cam[c].initialControl.setFrameSyncMode(dai.CameraControl.FrameSyncMode.INPUT)` for multiple devices sync (frame time is aligned, exposure could be different per device) Note: sensor trigger pin reacts on rising edge signal, and keeping the line high will cause repeated triggering. * Pipeline: add `setImageManipCmxSizeAdjust` * FW: fixes for 48MP camera, FW build for previous commits * Fix ColorCamera::getSensorCrop calculation for AUTO, was returning zero * WIP - flashUserBootloader * Updated Bootloader and added example * Added monitor thread for DeviceBootloader * Added explicit isUserBootloader call * Updated Bootloader for better User Bootloader support * MonoCamera: add frame pool size config API * Removed device_information and multi_roi from tests * Updated FW with ImageManip dynamic memory allocation * Disabled LATEX generation for docs * Added Warp node * Applied style * Set Yolo default iou threshold to 0.5 * Exposed Bootloader version available when booting a device in bootloader state * [Warp] Exposed HW engines used and interpolation * ImgFrame: add `getColorTemperature`. FW: fix exp/iso report for MonoCamera * CameraControl: update API docs, specify some defaults * Rename CameraProperties -> CameraFeatures * Added a sign cast to max user bootloader size check * Revert "Pipeline: add `setImageManipCmxSizeAdjust`" This reverts commit 591a98b. * Fix typo and add calibration_factory_reset example * Don't use the example as a part of the testing suite Co-authored-by: TheMarpe <[email protected]> * DEPTHAI_DEBUG=1 env var to enable `logDevicePrints`, ColorCamera: THE_12P0_MP, THE_5312X6000 * Update FW, shared: clangformat * `make clangformat`: calibration_factory_reset.cpp, depthai-shared, FW: increase an internal queue size for frameEvent * Exposed Timesync configurability * Docs fixes * Add support for yolov6r2 parsing * Expand spatial image detections with original config * Update CPP examples * Add getTimestamp and getTimestampDevice getter to IMU packets * Update IMU examples * Add THE_1200_P for AR0234 MonoCamera * Several FW updates: - !!! For all sockets/cameras to be scanned, the EEPROM calib data boardName/productName should contain "FFC" or an FFC-related board name: 1090/2090/2088. Otherwise the behavior is to scan only for standard OAK devices sockets/cameras - Some more checks for the LCM48 (on MAX) supported resolutions - Fixes for RGB-mono SW-sync for standard OAK-D / OAK-D-Lite camera configs - AR0234 monochrome support, however needs an OV9282 enabled at the same time for now * Color/MonoCamera: handle some more cases for newly added resolutions/sockets * Update shared/FW after merge, fix error log printed for MonoCamera AUTO socket * Closes: #355 * Bump version to 2.18.0 * Updated FW with some Color/MonoCamera fixes * stability test * Update FW: - fix for high system load crash, especially on PoE devices - for for OV9282 as MonoCamera on RGB/CAM_A socket * stability test * Added a convinience setTimesync function * Added isUserBootloaderSupported to DeviceBootloader * Updated XLink with Windows improvements when scanning for already booted USB devices * Updated FW with device time reset on boot * Bump to v2.19.0 * Improved wording on unavailable devices * Fix yolo v5 decoding when there is a single class * FW: fixes for certain OV9782 and OV9282 permutations/configs, fix for OV9782/OV9282 alone failing on RGB/CAM_A socket * Update CI to Node16 compatible actions * Update FW: fix image size when decimation filter is enabled * Stability test - limit FPS (#633) * Print CPU usage * Limit the FPS so POE devices aren't maxed out * Increase FPS * Reverse changes to the system logger example Co-authored-by: TheMarpe <[email protected]> Co-authored-by: Matevz Morato <[email protected]> * Added getProductName * Renamed to getDeviceName and added some legacy handling * Updated FW with productName as protected field and ImageManip behavior revert * Updated style * Added IR driver support for new OAK-FFC 4P * FW: bugfix for device bootup with default static IP * OAK-FFC 4P R5M1E5 IR/Dot support * Bump to v2.19.1 * changed version and updated changelog Co-authored-by: alex-luxonis <[email protected]> Co-authored-by: TheMarpe <[email protected]> Co-authored-by: SzabolcsGergely <[email protected]> Co-authored-by: szabi-luxonis <[email protected]> Co-authored-by: Matevz Morato <[email protected]> Co-authored-by: moratom <[email protected]> Co-authored-by: TheMarpe <[email protected]> Co-authored-by: alex-luxonis <[email protected]>
1 parent 65cc544 commit 46de84b

File tree

9 files changed

+93
-8
lines changed

9 files changed

+93
-8
lines changed

CHANGELOG.rst

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,14 @@
22
Changelog for package depthai
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.19.1 (2022-11-28)
6+
-----------
7+
* Added Device getDeviceName API
8+
* OAK-FFC 4P (R5M1E5) IR/Dot support
9+
* Additional Stability bugfixes to go along with 2.19.0 for PoE devices
10+
* Protected productName field in EEPROM
11+
* Contributors: Alex Bougdan, Szabolcs Gergely, Martin Peterlin
12+
513

614
2.19.0 (2022-09-20)
715
-----------

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ if(WIN32)
4343
endif()
4444

4545
# Create depthai project
46-
project(depthai VERSION "2.19.0" LANGUAGES CXX C)
46+
project(depthai VERSION "2.19.1" LANGUAGES CXX C)
4747
get_directory_property(has_parent PARENT_DIRECTORY)
4848
if(has_parent)
4949
set(DEPTHAI_VERSION ${PROJECT_VERSION} PARENT_SCOPE)

cmake/Depthai/DepthaiDeviceSideConfig.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
set(DEPTHAI_DEVICE_SIDE_MATURITY "snapshot")
33

44
# "full commit hash of device side binary"
5-
set(DEPTHAI_DEVICE_SIDE_COMMIT "b3aeaf23ff5857fc8f79d412ceefc08da23e7aad")
5+
set(DEPTHAI_DEVICE_SIDE_COMMIT "adbcc016c8bd5a5580a26d8b6250f77160203666")
66

77
# "version if applicable"
88
set(DEPTHAI_DEVICE_SIDE_VERSION "")

examples/ColorCamera/rgb_preview.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@ int main() {
4141
cout << "Bootloader version: " << device.getBootloaderVersion()->toString() << endl;
4242
}
4343

44+
// Device name
45+
cout << "Device name: " << device.getDeviceName() << endl;
46+
4447
// Output queue will be used to get the rgb frames from the output defined above
4548
auto qRgb = device.getOutputQueue("rgb", 4, false);
4649

include/depthai/device/CalibrationHandler.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ namespace dai {
1919
* - batchName
2020
* - batchTime
2121
* - boardOptions
22+
* - productName
2223
*/
2324
class CalibrationHandler {
2425
public:

include/depthai/device/DeviceBase.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -373,6 +373,12 @@ class DeviceBase {
373373
*/
374374
DeviceInfo getDeviceInfo() const;
375375

376+
/**
377+
* Get device name if available
378+
* @returns device name or empty string if not available
379+
*/
380+
std::string getDeviceName();
381+
376382
/**
377383
* Get MxId of device
378384
*

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
<package format="3">
22
<name>depthai</name>
3-
<version>2.19.0</version>
3+
<version>2.19.1</version>
44
<description>DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform</description>
55

66
<maintainer email="[email protected]">Sachin Guruswamy</maintainer>

src/device/DeviceBase.cpp

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -892,6 +892,34 @@ DeviceInfo DeviceBase::getDeviceInfo() const {
892892
return deviceInfo;
893893
}
894894

895+
std::string DeviceBase::getDeviceName() {
896+
checkClosed();
897+
898+
std::string deviceName;
899+
EepromData eeprom = readFactoryCalibrationOrDefault().getEepromData();
900+
if((deviceName = eeprom.productName).empty()) {
901+
eeprom = readCalibrationOrDefault().getEepromData();
902+
if((deviceName = eeprom.productName).empty()) {
903+
deviceName = eeprom.boardName;
904+
}
905+
}
906+
907+
// Convert to device naming from display/product naming
908+
std::transform(deviceName.begin(), deviceName.end(), deviceName.begin(), std::ptr_fun<int, int>(std::toupper));
909+
std::replace(deviceName.begin(), deviceName.end(), ' ', '-');
910+
911+
// Handle some known legacy cases
912+
if(deviceName == "BW1098OBC") {
913+
deviceName = "OAK-D";
914+
} else if(deviceName == "DM2097") {
915+
deviceName = "OAK-D-CM4-POE";
916+
} else if(deviceName == "BW1097") {
917+
deviceName = "OAK-D-CM3";
918+
}
919+
920+
return deviceName;
921+
}
922+
895923
void DeviceBase::setLogOutputLevel(LogLevel level) {
896924
checkClosed();
897925

tests/src/stability_stress_test.cpp

Lines changed: 44 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,24 @@
1313
#include <opencv2/opencv.hpp>
1414
#endif
1515

16+
static constexpr int RGB_FPS = 20;
17+
static constexpr int MONO_FPS = 20;
18+
static constexpr int ENCODER_FPS = 10;
19+
20+
void printSystemInformation(dai::SystemInformation info) {
21+
printf("Ddr used / total - %.2f / %.2f MiB\n", info.ddrMemoryUsage.used / (1024.0f * 1024.0f), info.ddrMemoryUsage.total / (1024.0f * 1024.0f));
22+
printf("Cmx used / total - %.2f / %.2f MiB\n", info.cmxMemoryUsage.used / (1024.0f * 1024.0f), info.cmxMemoryUsage.total / (1024.0f * 1024.0f));
23+
printf("LeonCss heap used / total - %.2f / %.2f MiB\n",
24+
info.leonCssMemoryUsage.used / (1024.0f * 1024.0f),
25+
info.leonCssMemoryUsage.total / (1024.0f * 1024.0f));
26+
printf("LeonMss heap used / total - %.2f / %.2f MiB\n",
27+
info.leonMssMemoryUsage.used / (1024.0f * 1024.0f),
28+
info.leonMssMemoryUsage.total / (1024.0f * 1024.0f));
29+
const auto& t = info.chipTemperature;
30+
printf("Chip temperature - average: %.2f, css: %.2f, mss: %.2f, upa: %.2f, dss: %.2f\n", t.average, t.css, t.mss, t.upa, t.dss);
31+
printf("Cpu usage - Leon CSS: %.2f %%, Leon MSS: %.2f %%\n", info.leonCssCpuUsage.average * 100, info.leonMssCpuUsage.average * 100);
32+
}
33+
1634
static const std::vector<std::string> labelMap = {
1735
"person", "bicycle", "car", "motorbike", "aeroplane", "bus", "train", "truck", "boat",
1836
"traffic light", "fire hydrant", "stop sign", "parking meter", "bench", "bird", "cat", "dog", "horse",
@@ -63,6 +81,7 @@ int main(int argc, char** argv) {
6381
auto edgeDetectorLeft = pipeline.create<dai::node::EdgeDetector>();
6482
auto edgeDetectorRight = pipeline.create<dai::node::EdgeDetector>();
6583
auto edgeDetectorRgb = pipeline.create<dai::node::EdgeDetector>();
84+
auto sysLog = pipeline.create<dai::node::SystemLogger>();
6685
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
6786
auto script1 = pipeline.create<dai::node::Script>();
6887
auto script2 = pipeline.create<dai::node::Script>();
@@ -84,6 +103,7 @@ int main(int argc, char** argv) {
84103
auto xoutEdgeLeft = pipeline.create<dai::node::XLinkOut>();
85104
auto xoutEdgeRight = pipeline.create<dai::node::XLinkOut>();
86105
auto xoutEdgeRgb = pipeline.create<dai::node::XLinkOut>();
106+
auto xoutSysLog = pipeline.create<dai::node::XLinkOut>();
87107
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
88108
auto scriptOut = pipeline.create<dai::node::XLinkOut>();
89109
auto scriptOut2 = pipeline.create<dai::node::XLinkOut>();
@@ -97,6 +117,7 @@ int main(int argc, char** argv) {
97117
xoutDepth->setStreamName("depth");
98118
xoutNN->setStreamName("detections");
99119
xoutRgb->setStreamName("rgb");
120+
xoutSysLog->setStreamName("sysinfo");
100121
const auto edgeLeftStr = "edge left";
101122
const auto edgeRightStr = "edge right";
102123
const auto edgeRgbStr = "edge rgb";
@@ -117,17 +138,20 @@ int main(int argc, char** argv) {
117138
camRgb->setPreviewSize(416, 416);
118139
camRgb->setInterleaved(false);
119140
camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR);
141+
camRgb->setFps(RGB_FPS);
120142

121143
monoLeft->setBoardSocket(dai::CameraBoardSocket::LEFT);
122144
monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
145+
monoLeft->setFps(MONO_FPS);
123146

124147
monoRight->setBoardSocket(dai::CameraBoardSocket::RIGHT);
125148
monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
149+
monoRight->setFps(MONO_FPS);
126150

127151
// Setting to 26fps will trigger error
128-
ve1->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H264_MAIN);
129-
ve2->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H265_MAIN);
130-
ve3->setDefaultProfilePreset(25, dai::VideoEncoderProperties::Profile::H264_MAIN);
152+
ve1->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H264_MAIN);
153+
ve2->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H265_MAIN);
154+
ve3->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H264_MAIN);
131155

132156
stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
133157
// Align depth map to the perspective of RGB camera, on which inference is done
@@ -150,6 +174,8 @@ int main(int argc, char** argv) {
150174

151175
edgeDetectorRgb->setMaxOutputFrameSize(8294400);
152176

177+
sysLog->setRate(0.2f);
178+
153179
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
154180
std::string source1 = R"(
155181
import time
@@ -250,6 +276,9 @@ int main(int argc, char** argv) {
250276
camRgb->video.link(edgeDetectorRgb->inputImage);
251277
edgeDetectorLeft->outputImage.link(xoutEdgeLeft->input);
252278
edgeDetectorRight->outputImage.link(xoutEdgeRight->input);
279+
sysLog->out.link(xoutSysLog->input);
280+
xoutSysLog->input.setBlocking(false);
281+
xoutSysLog->input.setQueueSize(1);
253282

254283
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
255284
script1->outputs["out"].link(script2->inputs["in"]);
@@ -269,6 +298,8 @@ int main(int argc, char** argv) {
269298
// Connect to device and start pipeline
270299
dai::Device device(pipeline);
271300

301+
auto usb_speed = device.getUsbSpeed();
302+
272303
// Output queues will be used to get the encoded data from the output defined above
273304
auto outQ1 = device.getOutputQueue("ve1Out", 30, false);
274305
auto outQ2 = device.getOutputQueue("ve2Out", 30, false);
@@ -279,7 +310,7 @@ int main(int argc, char** argv) {
279310
auto edgeLeftQueue = device.getOutputQueue(edgeLeftStr, 8, false);
280311
auto edgeRightQueue = device.getOutputQueue(edgeRightStr, 8, false);
281312
auto edgeRgbQueue = device.getOutputQueue(edgeRgbStr, 8, false);
282-
313+
auto qSysInfo = device.getOutputQueue("sysinfo", 4, false);
283314
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
284315
auto scriptQueue = device.getOutputQueue("script", 8, false);
285316
auto script2Queue = device.getOutputQueue("script2", 8, false);
@@ -298,7 +329,7 @@ int main(int argc, char** argv) {
298329
mutex countersMtx;
299330
unordered_map<std::string, int> counters;
300331

301-
thread countingThread([&countersMtx, &counters, &device, TEST_TIMEOUT]() {
332+
thread countingThread([&countersMtx, &counters, &device, &usb_speed, TEST_TIMEOUT]() {
302333
// Initial delay
303334
this_thread::sleep_for(5s);
304335

@@ -310,6 +341,7 @@ int main(int argc, char** argv) {
310341

311342
bool failed = counters.size() == 0;
312343
cout << "[" << duration_cast<seconds>(steady_clock::now() - timeoutStopwatch).count() << "s] "
344+
<< "Usb speed " << usb_speed << " "
313345
<< "FPS: ";
314346
for(const auto& kv : counters) {
315347
if(kv.second == 0) {
@@ -353,6 +385,13 @@ int main(int argc, char** argv) {
353385
auto edgeLefts = edgeLeftQueue->tryGetAll<dai::ImgFrame>();
354386
auto edgeRights = edgeRightQueue->tryGetAll<dai::ImgFrame>();
355387

388+
auto sysInfo = qSysInfo->tryGet<dai::SystemInformation>();
389+
if(sysInfo) {
390+
printf("----------------------------------------\n");
391+
std::cout << "Usb speed: " << usb_speed << std::endl;
392+
printSystemInformation(*sysInfo);
393+
printf("----------------------------------------\n");
394+
}
356395
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
357396
auto script = scriptQueue->tryGetAll<dai::Buffer>();
358397
auto script2 = script2Queue->tryGetAll<dai::Buffer>();

0 commit comments

Comments
 (0)