Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Release v2.29.0 #1168

Merged
merged 48 commits into from
Nov 22, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
48 commits
Select commit Hold shift + click to select a range
41feacd
CameraControl: add API to set/handle miscellaneous controls
alex-luxonis May 4, 2023
3a202c7
FW: IMX378/IMX582 manual ISO up to 3200, handle miscellaneous controls:
alex-luxonis May 12, 2023
7dfa8ea
FW: IMX378/IMX582 manual ISO up to 35000, higher than 3200 only with …
alex-luxonis May 12, 2023
f02126f
FW: IMX586 on-sensor HDR, with new misc controls:
alex-luxonis May 27, 2023
378a690
FW: initial IMX678 support (4K). TMP IMX462 enable HCG (high conversi…
alex-luxonis Feb 2, 2024
b58beda
Merge 'origin/develop' into camera_controls_misc
alex-luxonis Feb 7, 2024
669f067
Merge 'origin/imx678' into camera_controls_misc
alex-luxonis Feb 7, 2024
13d7ae5
Merge 'origin/tof_intensity' into camera_controls_misc. FIX for broke…
alex-luxonis Feb 7, 2024
2595d56
"high-conversion-gain" camera misc control for IMX462 and IMX678, ena…
alex-luxonis Feb 7, 2024
198c6bc
FW: initial support for IMX715, 4lane, 4K, max FPS 9.7 for now
alex-luxonis Feb 8, 2024
ffd129f
FW: IMX678 binning option (1080p, 60fps), IMX582 HDR:
alex-luxonis Feb 9, 2024
cbbe866
Add runtime stereo calib reconfig
SzabolcsGergely May 10, 2024
900aeb3
Merge remote-tracking branch 'origin/develop' into HEAD
SzabolcsGergely Jun 4, 2024
79ec49b
Remove tailing ;
SzabolcsGergely Jun 4, 2024
dc03563
FW: AR0234 tuning increase max exposure: 33 -> 890 ms
alex-luxonis Aug 19, 2024
c17a80e
FW: fix ToF EEPROM reading for certain FFC camera permutations
alex-luxonis Aug 22, 2024
694710e
Merge 'origin/develop' into camera_controls_misc
alex-luxonis Aug 22, 2024
73a77d4
FW: update after merge, add "3a-follow" misc control:
alex-luxonis Aug 26, 2024
04564df
FW: update after merge. Also fix colors for IMX378 THE_1352X1012 with…
alex-luxonis Sep 23, 2024
9b2725f
Merge pull request #972 from luxonis/camera_controls_misc
alex-luxonis Sep 23, 2024
7279816
CrashDump: disable on shutdown
SzabolcsGergely Sep 25, 2024
2e824de
FW: misc controls for multi-ToF staggering: frame-sync-id, frame-sync…
alex-luxonis Sep 25, 2024
e7c65ea
Merge remote-tracking branch 'origin/develop' into HEAD
SzabolcsGergely Sep 26, 2024
587821c
Merge pull request #1022 from luxonis/dynamic_calib
SzabolcsGergely Sep 26, 2024
89e9ee8
Format
Sep 30, 2024
15d6a79
SpeckleFilter: Add differenceThreshold config
SzabolcsGergely Oct 3, 2024
76e5cbd
Implement configurable filtering order
SzabolcsGergely Oct 4, 2024
7e11d06
Stereo: Scale disparity to 13 bit range prior to filtering
SzabolcsGergely Oct 9, 2024
bc7c7cc
StereoDepth: postprocessing: handle edge case when post-processing fi…
SzabolcsGergely Oct 11, 2024
69f7669
StereoDepth postprocessing: improve SpatialFilt/er and TemporalFilter…
SzabolcsGergely Oct 17, 2024
60d84e7
StereoDepth: add arbitrary filtering order support with scaling
SzabolcsGergely Oct 21, 2024
acafbab
FW: Stereo: issue debug prints once on calibration update event
SzabolcsGergely Oct 29, 2024
71b80f9
Merge remote-tracking branch 'origin/develop' into HEAD
SzabolcsGergely Nov 7, 2024
02f004d
Stereo: Core: add new stereo presets
SzabolcsGergely Nov 7, 2024
b0b4d49
Merge pull request #1151 from luxonis/stereo_filter_improvements
SzabolcsGergely Nov 8, 2024
6656793
Bump version to 2.29.0
Nov 10, 2024
93a537d
Merge remote-tracking branch 'origin/main' into release_v2.29.0
Nov 10, 2024
898f086
Stereo: PostProcessing: Handle edge case
SzabolcsGergely Nov 11, 2024
ccbfbc1
Merge remote-tracking branch 'origin/develop' into release_v2.29.0
Nov 11, 2024
36d3743
Stereo: PostProcess: Fix edge case when decimation is before median
SzabolcsGergely Nov 12, 2024
fe5b1fb
StereoDepth: update getMaxDisparity
SzabolcsGergely Nov 12, 2024
869d0ee
Merge remote-tracking branch 'origin/develop' into release_v2.29.0
Nov 12, 2024
0a65ae4
Add width and height to encoded frame
asahtik Nov 14, 2024
9994eb3
Merge pull request #1174 from luxonis/encframe_add_width_height
asahtik Nov 15, 2024
b3a778f
Update stereo profile presets
SzabolcsGergely Nov 18, 2024
1c9229b
Remove HIGH_ACCURACY2
SzabolcsGergely Nov 18, 2024
79de99d
[FW] - add logs for timing of stereo filters
Nov 21, 2024
68fe9be
Remove unused preset modes
Nov 22, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ if(WIN32)
endif()

# Create depthai project
project(depthai VERSION "2.28.0" LANGUAGES CXX C)
project(depthai VERSION "2.29.0" 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 "9ed7c9ae4c232ff93a3500a585a6b1c00650e22c")
set(DEPTHAI_DEVICE_SIDE_COMMIT "4d360b5c56225f23e9a3d3a3999ce46c90cfdeaf")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
17 changes: 17 additions & 0 deletions include/depthai/device/DeviceBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -758,6 +758,23 @@ class DeviceBase {
*/
void flashCalibration2(CalibrationHandler calibrationDataHandler);

/**
* Sets the Calibration at runtime. This is not persistent and will be lost after device reset.
*
* @throws std::runtime_exception if failed to set the calibration
* @param calibrationObj CalibrationHandler object which is loaded with calibration information.
*
*/
void setCalibration(CalibrationHandler calibrationDataHandler);

/**
* Retrieves the CalibrationHandler object containing the non-persistent calibration
*
* @throws std::runtime_exception if failed to get the calibration
* @returns The CalibrationHandler object containing the non-persistent calibration
*/
CalibrationHandler getCalibration();

/**
* Fetches the EEPROM data from the device and loads it into CalibrationHandler object
* If no calibration is flashed, it returns default
Expand Down
35 changes: 35 additions & 0 deletions include/depthai/pipeline/datatype/CameraControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,6 +292,41 @@ class CameraControl : public Buffer {
*/
CameraControl& setCaptureIntent(CaptureIntent mode);

/**
* Set a miscellaneous control. The controls set by this function get appended
* to a list, processed after the standard controls
* @param control Control name
* @param value Value as a string
*/
CameraControl& setMisc(std::string control, std::string value);

/**
* Set a miscellaneous control. The controls set by this function get appended
* to a list, processed after the standard controls
* @param control Control name
* @param value Value as an integer number
*/
CameraControl& setMisc(std::string control, int value);

/**
* Set a miscellaneous control. The controls set by this function get appended
* to a list, processed after the standard controls
* @param control Control name
* @param value Value as a floating point number
*/
CameraControl& setMisc(std::string control, float value);

/**
* Clear the list of miscellaneous controls set by `setControl`
*/
void clearMiscControls();

/**
* Get the list of miscellaneous controls set by `setControl`
* @returns A list of <key, value> pairs as strings
*/
std::vector<std::pair<std::string, std::string>> getMiscControls();

// Functions to retrieve properties
/**
* Check whether command to capture a still is set
Expand Down
23 changes: 23 additions & 0 deletions include/depthai/pipeline/datatype/EncodedFrame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,15 @@ class EncodedFrame : public Buffer {
* Retrieves instance number
*/
unsigned int getInstanceNum() const;
/**
* Retrieves image width in pixels
*/
unsigned int getWidth() const;

/**
* Retrieves image height in pixels
*/
unsigned int getHeight() const;
/**
* Retrieves exposure time
*/
Expand Down Expand Up @@ -111,6 +120,20 @@ class EncodedFrame : public Buffer {
*/
EncodedFrame& setInstanceNum(unsigned int instance);

/**
* Specifies frame width
*
* @param width frame width
*/
EncodedFrame& setWidth(unsigned int width);

/**
* Specifies frame height
*
* @param height frame height
*/
EncodedFrame& setHeight(unsigned int height);

/**
* Specifies the encoding quality
*
Expand Down
9 changes: 7 additions & 2 deletions include/depthai/pipeline/node/StereoDepth.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,16 @@ class StereoDepth : public NodeCRTP<Node, StereoDepth, StereoDepthProperties> {
/**
* Prefers accuracy over density. More invalid depth values, but less outliers.
*/
HIGH_ACCURACY,
HIGH_ACCURACY [[deprecated("Will be removed in future releases and replaced with DEFAULT")]],
/**
* Prefers density over accuracy. Less invalid depth values, but more outliers.
*/
HIGH_DENSITY
HIGH_DENSITY [[deprecated("Will be removed in future releases and replaced with DEFAULT")]],

DEFAULT,
FACE,
HIGH_DETAIL,
ROBOTICS
};

protected:
Expand Down
20 changes: 20 additions & 0 deletions src/device/DeviceBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1349,6 +1349,26 @@ void DeviceBase::flashCalibration2(CalibrationHandler calibrationDataHandler) {
}
}

void DeviceBase::setCalibration(CalibrationHandler calibrationDataHandler) {
bool success;
std::string errorMsg;
std::tie(success, errorMsg) = pimpl->rpcClient->call("setCalibration", calibrationDataHandler.getEepromData()).as<std::tuple<bool, std::string>>();
if(!success) {
throw std::runtime_error(errorMsg);
}
}

CalibrationHandler DeviceBase::getCalibration() {
bool success;
std::string errorMsg;
dai::EepromData eepromData;
std::tie(success, errorMsg, eepromData) = pimpl->rpcClient->call("getCalibration").as<std::tuple<bool, std::string, dai::EepromData>>();
if(!success) {
throw EepromError(errorMsg);
}
return CalibrationHandler(eepromData);
}

CalibrationHandler DeviceBase::readCalibration() {
dai::EepromData eepromData{};
try {
Expand Down
17 changes: 17 additions & 0 deletions src/pipeline/datatype/CameraControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,6 +215,23 @@ CameraControl& CameraControl::setCaptureIntent(CaptureIntent mode) {
return *this;
}

CameraControl& CameraControl::setMisc(std::string control, std::string value) {
cfg.miscControls.push_back(std::make_pair(control, value));
return *this;
}
CameraControl& CameraControl::setMisc(std::string control, int value) {
return setMisc(control, std::to_string(value));
}
CameraControl& CameraControl::setMisc(std::string control, float value) {
return setMisc(control, std::to_string(value));
}
void CameraControl::clearMiscControls() {
cfg.miscControls.clear();
}
std::vector<std::pair<std::string, std::string>> CameraControl::getMiscControls() {
return cfg.miscControls;
}

bool CameraControl::getCaptureStill() const {
return cfg.getCommand(RawCameraControl::Command::STILL_CAPTURE);
}
Expand Down
14 changes: 14 additions & 0 deletions src/pipeline/datatype/EncodedFrame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,12 @@ EncodedFrame::EncodedFrame(std::shared_ptr<RawEncodedFrame> ptr) : Buffer(std::m
unsigned int EncodedFrame::getInstanceNum() const {
return frame.instanceNum;
}
unsigned int EncodedFrame::getWidth() const {
return frame.width;
}
unsigned int EncodedFrame::getHeight() const {
return frame.height;
}
std::chrono::microseconds EncodedFrame::getExposureTime() const {
return std::chrono::microseconds(frame.cam.exposureTimeUs);
}
Expand Down Expand Up @@ -99,6 +105,14 @@ EncodedFrame& EncodedFrame::setInstanceNum(unsigned int instanceNum) {
frame.instanceNum = instanceNum;
return *this;
}
EncodedFrame& EncodedFrame::setWidth(unsigned int width) {
frame.width = width;
return *this;
}
EncodedFrame& EncodedFrame::setHeight(unsigned int height) {
frame.height = height;
return *this;
}
EncodedFrame& EncodedFrame::setQuality(unsigned int quality) {
frame.quality = quality;
return *this;
Expand Down
42 changes: 42 additions & 0 deletions src/pipeline/datatype/StereoDepthConfig.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,48 @@ float StereoDepthConfig::getMaxDisparity() const {
maxDisp += cfg.algorithmControl.disparityShift;
if(cfg.algorithmControl.enableExtended) maxDisp *= 2;
if(cfg.algorithmControl.enableSubpixel) maxDisp *= (1 << cfg.algorithmControl.subpixelFractionalBits);

std::vector<dai::StereoDepthConfig::PostProcessing::Filter> filtersToExecute;
for(auto filter : cfg.postProcessing.filteringOrder) {
switch(filter) {
case RawStereoDepthConfig::PostProcessing::Filter::SPECKLE:
if(cfg.postProcessing.speckleFilter.enable) {
filtersToExecute.push_back(filter);
}
break;
case RawStereoDepthConfig::PostProcessing::Filter::TEMPORAL:
if(cfg.postProcessing.temporalFilter.enable) {
filtersToExecute.push_back(filter);
}
break;
case RawStereoDepthConfig::PostProcessing::Filter::SPATIAL:
if(cfg.postProcessing.spatialFilter.enable) {
filtersToExecute.push_back(filter);
}
break;
case RawStereoDepthConfig::PostProcessing::Filter::DECIMATION:
if(cfg.postProcessing.decimationFilter.decimationFactor > 1) {
filtersToExecute.push_back(filter);
}
break;
case RawStereoDepthConfig::PostProcessing::Filter::MEDIAN:
if(cfg.postProcessing.median != dai::MedianFilter::MEDIAN_OFF) {
filtersToExecute.push_back(filter);
}
break;
case RawStereoDepthConfig::PostProcessing::Filter::NONE:
break;
default:
break;
}
}

if(filtersToExecute.size() != 0) {
if(filtersToExecute.back() != RawStereoDepthConfig::PostProcessing::Filter::MEDIAN) {
maxDisp = 1 << 13;
}
}

return maxDisp;
}

Expand Down
Loading
Loading