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 14 commits
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 "8d27dfe16cbb72fa2649b87385a5a726127c4cfa")
set(DEPTHAI_DEVICE_SIDE_COMMIT "80b63be3ce97dc177df17865da85403ff08348ca")

# "version if applicable"
set(DEPTHAI_DEVICE_SIDE_VERSION "")
50 changes: 22 additions & 28 deletions include/depthai/pipeline/datatype/CameraControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,10 +105,10 @@ class CameraControl : public Buffer {
void setAutoExposureRegion(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height);

/**
* Set a command to specify auto exposure compenstaion
* @param compensation Compensation value between -128..127
* Set a command to specify auto exposure compensation
* @param compensation Compensation value between -9..9
*/
void setAutoExposureCompensation(int8_t compensation);
void setAutoExposureCompensation(int compensation);

/**
* Set a command to specify auto banding mode
Expand All @@ -119,7 +119,7 @@ class CameraControl : public Buffer {
/**
* Set a command to manually specify exposure
* @param exposureTimeUs Exposure time in microseconds
* @param sensitivityIso Sensitivity as ISO value
* @param sensitivityIso Sensitivity as ISO value, usual range 100..1600
*/
void setManualExposure(uint32_t exposureTimeUs, uint32_t sensitivityIso);

Expand All @@ -138,46 +138,40 @@ class CameraControl : public Buffer {

// Other image controls
/**
* Set a command to specify auto white balance lock
* @param lock Auto white balance lock mode enabled or disabled
*/
void setBrightness(uint16_t value); // TODO move to AE?

/**
* Set a command to specify auto white balance lock
* @param lock Auto white balance lock mode enabled or disabled
* Set a command to adjust image brightness
* @param value Brightness, range -10..10
*/
void setContrast(uint16_t value);
void setBrightness(int value);

/**
* Set a command to specify saturation value
* @param value Saturation
* Set a command to adjust image contrast
* @param value Contrast, range -10..10
*/
void setSaturation(uint16_t value);
void setContrast(int value);

/**
* Set a command to specify sharpness value
* @param value Sharpness
* Set a command to adjust image saturation
* @param value Saturation, range -10..10
*/
void setSharpness(uint16_t value);
void setSaturation(int value);

/**
* Set a command to specify noise reduction strength
* @param value Noise reduction strength
* Set a command to adjust image sharpness
* @param value Sharpness, range 0..4
*/
void setNoiseReductionStrength(uint16_t value);
void setSharpness(int value);

/**
* Set a command to specify luma denoise value
* @param value Luma denoise
* Set a command to adjust luma denoise amount
* @param value Luma denoise amount, range 0..4
*/
void setLumaDenoise(uint16_t value);
void setLumaDenoise(int value);

/**
* Set a command to specify chroma denoise value
* @param value Chroma denoise
* Set a command to adjust chroma denoise amount
* @param value Chroma denoise amount, range 0..4
*/
void setChromaDenoise(uint16_t value);
void setChromaDenoise(int value);

/**
* Set a command to specify scene mode
Expand Down
52 changes: 52 additions & 0 deletions include/depthai/pipeline/node/ColorCamera.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ class ColorCamera : public Node {

std::shared_ptr<RawCameraControl> rawControl;

int getScaledSize(int input, int num, int denom) const;

public:
/**
* Constructs ColorCamera node.
Expand Down Expand Up @@ -71,6 +73,20 @@ class ColorCamera : public Node {
*/
Output still{*this, "still", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};

/**
* Outputs ImgFrame message that carries YUV420 planar (I420/IYUV) frame data.
*
* Generated by the ISP engine, and the source for the 'video', 'preview' and 'still' outputs
*/
Output isp{*this, "isp", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};

/**
* Outputs ImgFrame message that carries RAW10-packed (MIPI CSI-2 format) frame data.
*
* Captured directly from the camera sensor, and the source for the 'isp' output.
*/
Output raw{*this, "raw", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}};

/**
* Specify which board socket to use
* @param boardSocket Board socket to use
Expand Down Expand Up @@ -116,18 +132,47 @@ class ColorCamera : public Node {
/// Set preview output size
void setPreviewSize(int width, int height);

/// Set preview output size, as a tuple <width, height>
void setPreviewSize(std::tuple<int, int> size);

/// Set video output size
void setVideoSize(int width, int height);

/// Set video output size, as a tuple <width, height>
void setVideoSize(std::tuple<int, int> size);

/// Set still output size
void setStillSize(int width, int height);

/// Set still output size, as a tuple <width, height>
void setStillSize(std::tuple<int, int> size);

/// Set sensor resolution
void setResolution(Properties::SensorResolution resolution);

/// Get sensor resolution
Properties::SensorResolution getResolution() const;

/**
* Set 'isp' output scaling (numerator/denominator), preserving the aspect ratio.
* @param numerator Range 1..16
* @param denominator Range 1..63
*/
void setIspScale(int numerator, int denominator);

/// Set 'isp' output scaling, as a tuple <numerator, denominator>
void setIspScale(std::tuple<int, int> scale);

/**
* Set 'isp' output scaling, per each direction. If the horizontal scaling factor
* (horizNum/horizDen) is different than the vertical scaling factor
* (vertNum/vertDen), a distorted (stretched or squished) image is generated
*/
void setIspScale(int horizNum, int horizDenom, int vertNum, int vertDenom);

/// Set 'isp' output scaling, per each direction, as <numerator, denominator> tuples
void setIspScale(std::tuple<int, int> horizScale, std::tuple<int, int> vertScale);

/**
* Set rate at which camera should produce frames
* @param fps Rate in frames per second
Expand Down Expand Up @@ -168,6 +213,13 @@ class ColorCamera : public Node {
/// Get sensor resolution height
int getResolutionHeight() const;

/// Get 'isp' output resolution as size, after scaling
std::tuple<int, int> getIspSize() const;
/// Get 'isp' output width
int getIspWidth() const;
/// Get 'isp' output height
int getIspHeight() const;

/**
* Specify sensor center crop.
* Resolution size / video size
Expand Down
21 changes: 17 additions & 4 deletions include/depthai/pipeline/node/StereoDepth.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,17 @@ class StereoDepth : public Node {
*/
void setMedianFilter(Properties::MedianFilter median);

/**
* @param align Set the disparity/depth alignment: centered (between the 'left' and 'right' inputs),
* or from the perspective of a rectified output stream
*/
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.


/**
* @param camera Set the camera from whose perspective the disparity/depth will be aligned
*/
void setDepthAlign(CameraBoardSocket camera);

/**
* Confidence threshold for disparity calculation
* @param confThr Confidence threshold value 0..255
Expand Down Expand Up @@ -138,15 +149,17 @@ class StereoDepth : public Node {
void setRectifyMirrorFrame(bool enable);

/**
* Enable outputting rectified frames. Optimizes computation on device side when disabled
* Enable outputting rectified frames. Optimizes computation on device side when disabled.
* DEPRECATED. The outputs are auto-enabled if used
*/
void setOutputRectified(bool enable);
[[deprecated("Function call should be removed")]] void setOutputRectified(bool enable);

/**
* Enable outputting 'depth' stream (converted from disparity).
* In certain configurations, this will disable 'disparity' stream
* In certain configurations, this will disable 'disparity' stream.
* DEPRECATED. The output is auto-enabled if used
*/
void setOutputDepth(bool enable);
[[deprecated("Function call should be removed")]] void setOutputDepth(bool enable);
};

} // namespace node
Expand Down
18 changes: 7 additions & 11 deletions src/pipeline/datatype/CameraControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void CameraControl::setAutoExposureRegion(uint16_t startX, uint16_t startY, uint
cfg.aeRegion.height = height;
cfg.aeRegion.priority = 1; // TODO
}
void CameraControl::setAutoExposureCompensation(int8_t compensation) {
void CameraControl::setAutoExposureCompensation(int compensation) {
cfg.setCommand(RawCameraControl::Command::EXPOSURE_COMPENSATION);
cfg.expCompensation = compensation;
}
Expand All @@ -87,31 +87,27 @@ void CameraControl::setAutoWhiteBalanceLock(bool lock) {
}

// Other image controls
void CameraControl::setBrightness(uint16_t value) {
void CameraControl::setBrightness(int value) {
cfg.setCommand(RawCameraControl::Command::BRIGHTNESS);
cfg.brightness = value;
}
void CameraControl::setContrast(uint16_t value) {
void CameraControl::setContrast(int value) {
cfg.setCommand(RawCameraControl::Command::CONTRAST);
cfg.contrast = value;
}
void CameraControl::setSaturation(uint16_t value) {
void CameraControl::setSaturation(int value) {
cfg.setCommand(RawCameraControl::Command::SATURATION);
cfg.saturation = value;
}
void CameraControl::setSharpness(uint16_t value) {
void CameraControl::setSharpness(int value) {
cfg.setCommand(RawCameraControl::Command::SHARPNESS);
cfg.sharpness = value;
}
void CameraControl::setNoiseReductionStrength(uint16_t value) {
cfg.setCommand(RawCameraControl::Command::NOISE_REDUCTION_STRENGTH);
cfg.noiseReductionStrength = value;
}
void CameraControl::setLumaDenoise(uint16_t value) {
void CameraControl::setLumaDenoise(int value) {
cfg.setCommand(RawCameraControl::Command::LUMA_DENOISE);
cfg.lumaDenoise = value;
}
void CameraControl::setChromaDenoise(uint16_t value) {
void CameraControl::setChromaDenoise(int value) {
cfg.setCommand(RawCameraControl::Command::CHROMA_DENOISE);
cfg.chromaDenoise = value;
}
Expand Down
61 changes: 60 additions & 1 deletion src/pipeline/node/ColorCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ std::string ColorCamera::getName() const {
}

std::vector<Node::Output> ColorCamera::getOutputs() {
return {video, preview, still};
return {raw, isp, video, preview, still};
}

std::vector<Node::Input> ColorCamera::getInputs() {
Expand Down Expand Up @@ -122,18 +122,49 @@ void ColorCamera::setPreviewSize(int width, int height) {
properties.previewHeight = height;
}

void ColorCamera::setPreviewSize(std::tuple<int, int> size) {
setPreviewSize(std::get<0>(size), std::get<1>(size));
}

// set video output size
void ColorCamera::setVideoSize(int width, int height) {
properties.videoWidth = width;
properties.videoHeight = height;
}

void ColorCamera::setVideoSize(std::tuple<int, int> size) {
setVideoSize(std::get<0>(size), std::get<1>(size));
}

// set still output size
void ColorCamera::setStillSize(int width, int height) {
properties.stillWidth = width;
properties.stillHeight = height;
}

void ColorCamera::setStillSize(std::tuple<int, int> size) {
setStillSize(std::get<0>(size), std::get<1>(size));
}

void ColorCamera::setIspScale(int horizNum, int horizDenom, int vertNum, int vertDenom) {
properties.ispScale.horizNumerator = horizNum;
properties.ispScale.horizDenominator = horizDenom;
properties.ispScale.vertNumerator = vertNum;
properties.ispScale.vertDenominator = vertDenom;
}

void ColorCamera::setIspScale(int numerator, int denominator) {
setIspScale(numerator, denominator, numerator, denominator);
}

void ColorCamera::setIspScale(std::tuple<int, int> scale) {
setIspScale(std::get<0>(scale), std::get<1>(scale));
}

void ColorCamera::setIspScale(std::tuple<int, int> horizScale, std::tuple<int, int> vertScale) {
setIspScale(std::get<0>(horizScale), std::get<1>(horizScale), std::get<0>(vertScale), std::get<1>(vertScale));
}

void ColorCamera::setResolution(ColorCameraProperties::SensorResolution resolution) {
properties.resolution = resolution;
}
Expand Down Expand Up @@ -251,6 +282,34 @@ int ColorCamera::getResolutionHeight() const {
return std::get<1>(getResolutionSize());
}

int ColorCamera::getScaledSize(int input, int num, int denom) const {
return (input * num - 1) / denom + 1;
}

int ColorCamera::getIspWidth() const {
int inW = getResolutionWidth();
int num = properties.ispScale.horizNumerator;
int den = properties.ispScale.horizDenominator;
if(num > 0 && den > 0) {
return getScaledSize(inW, num, den);
}
return inW;
}

int ColorCamera::getIspHeight() const {
int inH = getResolutionHeight();
int num = properties.ispScale.vertNumerator;
int den = properties.ispScale.vertDenominator;
if(num > 0 && den > 0) {
return getScaledSize(inH, num, den);
}
return inH;
}

std::tuple<int, int> ColorCamera::getIspSize() const {
return {getIspWidth(), getIspHeight()};
}

void ColorCamera::sensorCenterCrop() {
properties.sensorCropX = ColorCameraProperties::AUTO;
properties.sensorCropY = ColorCameraProperties::AUTO;
Expand Down
Loading