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

Fixes and improvements for StereoDepth, ColorCamera #82

Merged
merged 32 commits into from
Apr 28, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
db02740
ColorCamera: add `isp`, `raw` outputs
alex-luxonis Jan 7, 2021
ea9a98b
ColorCamera: add setIspScale/setIspScaleFull API
alex-luxonis Feb 11, 2021
0431b74
StereoDepth: deprecate setOutputDepth/Rectified
alex-luxonis Mar 9, 2021
5f2f312
ColorCamera: add API to get 'isp' scaled output size
alex-luxonis Mar 9, 2021
e04b257
`make clangformat`
alex-luxonis Mar 9, 2021
2f9ad0a
Update FW: stereo fixes, stereo/ColorCamera improvements
alex-luxonis Mar 9, 2021
f22ca12
Add API to configure disparity/depth alignment: left/right/center.
alex-luxonis Mar 13, 2021
4fc1433
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Mar 25, 2021
974dc98
StereoDepth: add overloaded setDepthAlign(CameraBoardSocket)
alex-luxonis Mar 25, 2021
4ec7f1f
StereoDepth: remove for now 'setBaselineOverrideCm', 'setFovOverrideD…
alex-luxonis Mar 25, 2021
ca3784b
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Mar 30, 2021
69726b3
Update FW: disparity (U8) aligning to RGB works.
alex-luxonis Mar 31, 2021
f809bb6
Address review comments:
alex-luxonis Mar 31, 2021
d4338e2
CameraControl: add ranges for extra controls,
alex-luxonis Mar 23, 2021
8c3a8e6
Add rgb_depth_aligned example
alex-luxonis Apr 1, 2021
29ca1c5
Fix conversion of YUV420p frames to OpenCV BGR,
alex-luxonis Apr 1, 2021
757d830
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 1, 2021
3964a7e
Examples: remove deprecated API setOutputDepth/Rectified
alex-luxonis Apr 1, 2021
fefb4b0
GitHub CI: limit cmake --parallel to 8 threads,
alex-luxonis Apr 1, 2021
878e4a6
README build snippets: limit `cmake --parallel` to 8
alex-luxonis Apr 1, 2021
b72bb07
Cleanup, remove some unused variables
alex-luxonis Apr 1, 2021
7df7402
Update FW: optimize depth align, make it work with subpixel/U16
alex-luxonis Apr 2, 2021
df43775
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 19, 2021
b0dd5d6
stereo_example: rectified flip no longer needed with LR-check on,
alex-luxonis Apr 21, 2021
6e11c1f
spatial_object_tracker example: remove deprecated setOutputDepth
alex-luxonis Apr 21, 2021
1e05f8c
fixed getting size of video/still when setting isp scaling
Erol444 Apr 24, 2021
3f2fb9d
Address review comments. Note:
alex-luxonis Apr 28, 2021
6d84ac9
clangformat cleanup
alex-luxonis Apr 27, 2021
f62304d
Update FW: fix still capture with scaling, add FPS capping (with warn…
alex-luxonis Apr 27, 2021
2e25a1e
Merge remote-tracking branch 'origin/develop' into stereo_fixes
alex-luxonis Apr 28, 2021
bf1cbdd
Update FW: fix ImageManip U16 crop (for depth/subpixel disparity)
alex-luxonis Apr 28, 2021
bffa915
Update FW, fix CI build: depthai-shared PR merged
alex-luxonis Apr 28, 2021
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 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 "665ede7a8669d441d02e4eb3be635b740d0ef190")
set(DEPTHAI_DEVICE_SIDE_COMMIT "0f1ac77644d6fd0ce75485e9fa20d7e34ae23ce7")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
5 changes: 5 additions & 0 deletions include/depthai/pipeline/node/StereoDepth.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,11 @@ class StereoDepth : public Node {
*/
void setMedianFilter(Properties::MedianFilter median);

/**
* @param align Set the disparity/depth alignment to the perspective of one camera
*/
void setDepthAlign(Properties::DepthAlign align);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should we use CameraBoardSocket to which to align to, instead of new DepthAlign enum?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Currently DepthAlign contains: { AUTO = -1, RIGHT, LEFT, CENTER, RGB }

  • RIGHT (default) and LEFT would map to the respective 'rectified' streams.
  • CENTER would just displace the disparity map (each pixel by its disparity_value / 2), while RGB (not yet implemented, defaulting with a warning to CENTER) would need an additional 'warp' step (extrinsics alignment / resolution scaling). For boards like BW1092 where the RGB camera is not centered, the disparity displacement would need to be done by a different amount.

Mapping to the real LEFT and RIGHT (from CameraBoardSocket), we would need to do and inverse homography transform, which should be easily doable with the mechanism for RGB in place. But it incurs the additional warp overhead, and in many cases it's not needed (as could be used directly with the rectified streams).

Should then we extend DepthAlign as: { AUTO = -1, RECTIFIED_RIGHT, RECTIFIED_LEFT, CENTER, RGB, LEFT, RIGHT } ?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What about if we separate this two to:

  • CameraBoardSocket <- which camera it references (can be up to number of MIPI lanes, not added yet to enum)
  • DepthAlign <- "mode" to referenced, like: RECTIFIED, ORIGINAL, CENTER, .. (TBD)

I think we'd cover all cases with this, without too much repetition.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Definitely adding a separate config with CameraBoardSocket is good, I will add it.

But one case where combining these two might be confusing is with e.g. CameraBoardSocket::RGB and mode: RECTIFIED.

Or with images from host, or running Stereo on OAK-1: one input from the RGB camera, the other from host (actually forwarded by another OAK-1), as one customer wants to use. Actually I think here we should have a way to pass a minimal StereoCalibration structure to StereoDepth, that won't refer to CameraBoardSocket entries, but simply to the 'left' and 'right' inputs to the node. We can discuss further on luxonis/depthai-shared#19

So I was thinking to reference based on the I/Os of the StereoDepth node. Something like
DepthAlign: RECTIFIED_RIGHT, RECTIFIED_LEFT, RECTIFIED_CENTER, INPUT_LEFT, INPUT_RIGHT, OTHER_CAMERA.

When OTHER_CAMERA is set, will specify it by CameraBoardSocket. And for example running standard stereo on OAK-D, INPUT_RIGHT would be equivalent to OTHER_CAMERA + CameraBoardSocket::RIGHT.

Thoughts on that? Also how to have the API, two separate functions, one with two parameters, or an overloaded function (pass either DepthAlign or CameraBoardSocket, and then remove OTHER_CAMERA)?
CC @saching13

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What martin suggested works best if we ignore the concept that left, and right are our two global shutter cameras.

In stereo node we set left camera and right camera using CameraBoardSocket and we have

DepthAlign <- "mode" to referenced, like: RECTIFIED, ORIGINAL, CENTER, .. (TBD)

In DepthAlign mode let's have only RECTIFIED_LEFT, RECTIFIED_RIGHT and CENTER.

And setAlignment(cameraBoardSocket) will make sure to align to any camera's that we have.
And another overload function or something like setExtendedAlignment takes DepthAlign mode. But in this case RECTIFIED_LEFT will be the rectified_left frame of the camera/image passed to the stereo left. and RECTIFIED_RIGHT will be the rectified_right frame of the camera/image passed as the right image to the stereo node.

One such case is where rgb camera can be stereo left and right camera can be stereo right.
And CENTER would not be the center of the device but the center of the stereo baseline.

Thoughts ?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Any resolution here? I think I've understood, and a lot of these are sounding good to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed as an overloaded function, as the options (DepthAlign and CameraBoardSocket) cannot be combined, and would be confusing to set both.


/**
* Confidence threshold for disparity calculation
* @param confThr Confidence threshold value 0..255
Expand Down
5 changes: 4 additions & 1 deletion src/pipeline/node/StereoDepth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,12 @@ void StereoDepth::setInputResolution(int width, int height) {
properties.width = width;
properties.height = height;
}
void StereoDepth::setMedianFilter(StereoDepthProperties::MedianFilter median) {
void StereoDepth::setMedianFilter(Properties::MedianFilter median) {
properties.median = median;
}
void StereoDepth::setDepthAlign(Properties::DepthAlign align) {
properties.depthAlign = align;
}
void StereoDepth::setConfidenceThreshold(int confThr) {
properties.confidenceThreshold = confThr;
}
Expand Down