Skip to content

Commit

Permalink
Ros release 2.19.1 (#649)
Browse files Browse the repository at this point in the history
* 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]>
  • Loading branch information
9 people authored Nov 28, 2022
1 parent 65cc544 commit 46de84b
Show file tree
Hide file tree
Showing 9 changed files with 93 additions and 8 deletions.
8 changes: 8 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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)
-----------
Expand Down
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion cmake/Depthai/DepthaiDeviceSideConfig.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -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 "")
3 changes: 3 additions & 0 deletions examples/ColorCamera/rgb_preview.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
1 change: 1 addition & 0 deletions include/depthai/device/CalibrationHandler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ namespace dai {
* - batchName
* - batchTime
* - boardOptions
* - productName
*/
class CalibrationHandler {
public:
Expand Down
6 changes: 6 additions & 0 deletions include/depthai/device/DeviceBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
*
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>depthai</name>
<version>2.19.0</version>
<version>2.19.1</version>
<description>DepthAI core is a C++ library which comes with firmware and an API to interact with OAK Platform</description>

<maintainer email="[email protected]">Sachin Guruswamy</maintainer>
Expand Down
28 changes: 28 additions & 0 deletions src/device/DeviceBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<int, int>(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();

Expand Down
49 changes: 44 additions & 5 deletions tests/src/stability_stress_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,24 @@
#include <opencv2/opencv.hpp>
#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<std::string> labelMap = {
"person", "bicycle", "car", "motorbike", "aeroplane", "bus", "train", "truck", "boat",
"traffic light", "fire hydrant", "stop sign", "parking meter", "bench", "bird", "cat", "dog", "horse",
Expand Down Expand Up @@ -63,6 +81,7 @@ int main(int argc, char** argv) {
auto edgeDetectorLeft = pipeline.create<dai::node::EdgeDetector>();
auto edgeDetectorRight = pipeline.create<dai::node::EdgeDetector>();
auto edgeDetectorRgb = pipeline.create<dai::node::EdgeDetector>();
auto sysLog = pipeline.create<dai::node::SystemLogger>();
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
auto script1 = pipeline.create<dai::node::Script>();
auto script2 = pipeline.create<dai::node::Script>();
Expand All @@ -84,6 +103,7 @@ int main(int argc, char** argv) {
auto xoutEdgeLeft = pipeline.create<dai::node::XLinkOut>();
auto xoutEdgeRight = pipeline.create<dai::node::XLinkOut>();
auto xoutEdgeRgb = pipeline.create<dai::node::XLinkOut>();
auto xoutSysLog = pipeline.create<dai::node::XLinkOut>();
#ifdef DEPTHAI_STABILITY_TEST_SCRIPT
auto scriptOut = pipeline.create<dai::node::XLinkOut>();
auto scriptOut2 = pipeline.create<dai::node::XLinkOut>();
Expand All @@ -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";
Expand All @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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"]);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -298,7 +329,7 @@ int main(int argc, char** argv) {
mutex countersMtx;
unordered_map<std::string, int> counters;

thread countingThread([&countersMtx, &counters, &device, TEST_TIMEOUT]() {
thread countingThread([&countersMtx, &counters, &device, &usb_speed, TEST_TIMEOUT]() {
// Initial delay
this_thread::sleep_for(5s);

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

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

auto sysInfo = qSysInfo->tryGet<dai::SystemInformation>();
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<dai::Buffer>();
auto script2 = script2Queue->tryGetAll<dai::Buffer>();
Expand Down

0 comments on commit 46de84b

Please sign in to comment.