@Namespace(value="dai::node") @NoOffset @Properties(inherit=depthai.class) public class StereoDepth extends StereoDepthPropertiesNode
| Modifier and Type | Class and Description |
|---|---|
static class |
StereoDepth.PresetMode
Preset modes for stereo depth.
|
Node.Connection, Node.DatatypeHierarchy, Node.Input, Node.InputMap, Node.Output, Node.OutputMapPointer.CustomDeallocator, Pointer.Deallocator, Pointer.NativeDeallocator, Pointer.ReferenceCounter| Constructor and Description |
|---|
StereoDepth(PipelineImpl par,
long nodeId) |
StereoDepth(PipelineImpl par,
long nodeId,
StereoDepthProperties props) |
StereoDepth(Pointer p)
Pointer cast constructor.
|
| Modifier and Type | Method and Description |
|---|---|
Node.Output |
confidenceMap()
Outputs ImgFrame message that carries RAW8 confidence map.
|
Node.Output |
debugDispCostDump()
Outputs ImgFrame message that carries cost dump of disparity map.
|
Node.Output |
debugDispLrCheckIt1()
Outputs ImgFrame message that carries left-right check first iteration (before combining with second iteration) disparity map.
|
Node.Output |
debugDispLrCheckIt2()
Outputs ImgFrame message that carries left-right check second iteration (before combining with first iteration) disparity map.
|
Node.Output |
debugExtDispLrCheckIt1()
Outputs ImgFrame message that carries extended left-right check first iteration (downscaled frame, before combining with second iteration) disparity map.
|
Node.Output |
debugExtDispLrCheckIt2()
Outputs ImgFrame message that carries extended left-right check second iteration (downscaled frame, before combining with first iteration) disparity map.
|
Node.Output |
depth()
Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in depth units (millimeter by default).
|
Node.Output |
disparity()
Outputs ImgFrame message that carries RAW8 / RAW16 encoded disparity data:
RAW8 encoded (0..95) for standard mode;
RAW8 encoded (0..190) for extended disparity mode;
RAW16 encoded for subpixel disparity mode:
- 0..760 for 3 fractional bits (by default)
- 0..1520 for 4 fractional bits
- 0..3040 for 5 fractional bits
|
void |
enableDistortionCorrection(boolean enableDistortionCorrection)
Equivalent to useHomographyRectification(!enableDistortionCorrection)
|
float |
getMaxDisparity()
Deprecated.
|
StereoDepthConfig |
initialConfig()
Initial config to use for StereoDepth.
|
Node.Input |
inputConfig()
Input StereoDepthConfig message with ability to modify parameters in runtime.
|
Node.Input |
left()
Input for left ImgFrame of left-right pair
Default queue is non-blocking with size 8
|
void |
loadMeshData(byte[] dataLeft,
byte[] dataRight) |
void |
loadMeshData(ByteBuffer dataLeft,
ByteBuffer dataRight) |
void |
loadMeshData(BytePointer dataLeft,
BytePointer dataRight)
Specify mesh calibration data for 'left' and 'right' inputs, as vectors of bytes.
|
void |
loadMeshFiles(Path pathLeft,
Path pathRight)
Specify local filesystem paths to the mesh calibration files for 'left' and 'right' inputs.
|
static BytePointer |
NAME() |
Node.Output |
outConfig()
Outputs StereoDepthConfig message that contains current stereo configuration.
|
Node.Output |
rectifiedLeft()
Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
|
Node.Output |
rectifiedRight()
Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.
|
Node.Input |
right()
Input for right ImgFrame of left-right pair
Default queue is non-blocking with size 8
|
void |
setAlphaScaling(float alpha)
Free scaling parameter between 0 (when all the pixels in the undistorted image are valid)
and 1 (when all the source image pixels are retained in the undistorted image).
|
void |
setBaseline(float baseline)
Override baseline from calibration.
|
void |
setConfidenceThreshold(int confThr)
Deprecated.
|
void |
setDefaultProfilePreset(int mode) |
void |
setDefaultProfilePreset(StereoDepth.PresetMode mode)
Sets a default preset based on specified option.
|
void |
setDepthAlign(depthai.CameraBoardSocket camera) |
void |
setDepthAlign(int camera) |
void |
setDepthAlign(RawStereoDepthConfig.AlgorithmControl.DepthAlign align) |
void |
setDepthAlignmentUseSpecTranslation(boolean specTranslation)
Use baseline information for depth alignment from specs (design data) or from calibration.
|
void |
setDisparityToDepthUseSpecTranslation(boolean specTranslation)
Use baseline information for disparity to depth conversion from specs (design data) or from calibration.
|
void |
setEmptyCalibration()
Deprecated.
|
void |
setExtendedDisparity(boolean enable)
Disparity range increased from 0-95 to 0-190, combined from full resolution and downscaled images.
|
void |
setFocalLength(float focalLength)
Override focal length from calibration.
|
void |
setFocalLengthFromCalibration(boolean focalLengthFromCalibration)
Deprecated.
|
void |
setInputResolution(int width,
int height)
Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
|
void |
setInputResolution(Pointer resolution)
Specify input resolution size
Optional if MonoCamera exists, otherwise necessary
|
void |
setLeftRightCheck(boolean enable)
Computes and combines disparities in both L-R and R-L directions, and combine them.
|
void |
setMedianFilter(depthai.MedianFilter median)
Deprecated.
|
void |
setMedianFilter(int median)
Deprecated.
|
void |
setMeshStep(int width,
int height)
Set the distance between mesh points.
|
void |
setNumFramesPool(int numFramesPool)
Specify number of frames in pool.
|
void |
setOutputDepth(boolean enable)
Deprecated.
|
void |
setOutputKeepAspectRatio(boolean keep)
Specifies whether the frames resized by
setOutputSize should preserve aspect ratio,
with potential cropping when enabled. |
void |
setOutputRectified(boolean enable)
Deprecated.
|
void |
setOutputSize(int width,
int height)
Specify disparity/depth output resolution size, implemented by scaling.
|
void |
setPostProcessingHardwareResources(int numShaves,
int numMemorySlices)
Specify allocated hardware resources for stereo depth.
|
void |
setRectification(boolean enable)
Rectify input images or not.
|
void |
setRectificationUseSpecTranslation(boolean specTranslation)
Obtain rectification matrices using spec translation (design data) or from calibration in calculations.
|
void |
setRectifyEdgeFillColor(int color)
Fill color for missing data at frame edges
|
void |
setRectifyMirrorFrame(boolean enable)
Deprecated.
|
void |
setRuntimeModeSwitch(boolean enable)
Enable runtime stereo mode switch, e.g.
|
void |
setSubpixel(boolean enable)
Computes disparity with sub-pixel interpolation (3 fractional bits by default).
|
void |
setSubpixelFractionalBits(int subpixelFractionalBits)
Number of fractional bits for subpixel mode.
|
Node.Output |
syncedLeft()
Passthrough ImgFrame message from 'left' Input.
|
Node.Output |
syncedRight()
Passthrough ImgFrame message from 'right' Input.
|
void |
useHomographyRectification(boolean useHomographyRectification)
Use 3x3 homography matrix for stereo rectification instead of sparse mesh generated on device.
|
clone, getName, properties, propertiesassetManager, getAssetManager, getInputRefs, getInputs, getOutputRefs, getOutputs, getParentPipeline, getProperties, getRequiredOpenVINOVersion, id, inputMapRefs, inputRefs, outputMapRefs, outputRefs, propertiesHolder, setInputMapRefs, setInputRefs, setOutputMapRefs, setOutputRefsaddress, asBuffer, asByteBuffer, availablePhysicalBytes, calloc, capacity, capacity, close, deallocate, deallocate, deallocateReferences, deallocator, deallocator, equals, fill, formatBytes, free, getDirectBufferAddress, getPointer, getPointer, getPointer, getPointer, hashCode, interruptDeallocatorThread, isNull, isNull, limit, limit, malloc, maxBytes, maxPhysicalBytes, memchr, memcmp, memcpy, memmove, memset, offsetAddress, offsetof, offsetof, parseBytes, physicalBytes, physicalBytesInaccurate, position, position, put, realloc, referenceCount, releaseReference, retainReference, setNull, sizeof, sizeof, toString, totalBytes, totalCount, totalPhysicalBytes, withDeallocator, zeropublic StereoDepth(Pointer p)
Pointer(Pointer).public StereoDepth(@SharedPtr PipelineImpl par, @Cast(value="int64_t") long nodeId)
public StereoDepth(@SharedPtr PipelineImpl par, @Cast(value="int64_t") long nodeId, @UniquePtr StereoDepthProperties props)
@MemberGetter @Cast(value="const char*") public static BytePointer NAME()
@MemberGetter @ByRef public StereoDepthConfig initialConfig()
@MemberGetter @ByRef public Node.Input inputConfig()
@MemberGetter @ByRef public Node.Input left()
@MemberGetter @ByRef public Node.Input right()
@MemberGetter @ByRef public Node.Output depth()
@MemberGetter @ByRef public Node.Output disparity()
@MemberGetter @ByRef public Node.Output syncedLeft()
@MemberGetter @ByRef public Node.Output syncedRight()
@MemberGetter @ByRef public Node.Output rectifiedLeft()
@MemberGetter @ByRef public Node.Output rectifiedRight()
@MemberGetter @ByRef public Node.Output outConfig()
@MemberGetter @ByRef public Node.Output debugDispLrCheckIt1()
@MemberGetter @ByRef public Node.Output debugDispLrCheckIt2()
@MemberGetter @ByRef public Node.Output debugExtDispLrCheckIt1()
@MemberGetter @ByRef public Node.Output debugExtDispLrCheckIt2()
@MemberGetter @ByRef public Node.Output debugDispCostDump()
@MemberGetter @ByRef public Node.Output confidenceMap()
@Deprecated public void setEmptyCalibration()
public void loadMeshFiles(@Const @ByRef Path pathLeft, @Const @ByRef Path pathRight)
setMeshStep.
With a 1280x800 resolution and the default (16,16) step, the required mesh size is:
width: 1280 / 16 + 1 = 81
height: 800 / 16 + 1 = 51public void loadMeshData(@Cast(value="std::uint8_t*") @StdVector BytePointer dataLeft, @Cast(value="std::uint8_t*") @StdVector BytePointer dataRight)
loadMeshFiles for the expected data formatpublic void loadMeshData(@Cast(value="std::uint8_t*") @StdVector ByteBuffer dataLeft, @Cast(value="std::uint8_t*") @StdVector ByteBuffer dataRight)
public void loadMeshData(@Cast(value="std::uint8_t*") @StdVector byte[] dataLeft, @Cast(value="std::uint8_t*") @StdVector byte[] dataRight)
public void setMeshStep(int width,
int height)
public void setInputResolution(int width,
int height)
public void setInputResolution(@ByVal @Cast(value="std::tuple<int,int>*") Pointer resolution)
public void setOutputSize(int width,
int height)
public void setOutputKeepAspectRatio(@Cast(value="bool") boolean keep)
setOutputSize should preserve aspect ratio,
with potential cropping when enabled. Default true@Deprecated public void setMedianFilter(depthai.MedianFilter median)
median - Set kernel size for disparity/depth median filtering, or disable@Deprecated public void setMedianFilter(@Cast(value="dai::MedianFilter") int median)
public void setDepthAlign(RawStereoDepthConfig.AlgorithmControl.DepthAlign align)
align - Set the disparity/depth alignment: centered (between the 'left' and 'right' inputs),
or from the perspective of a rectified output streampublic void setDepthAlign(depthai.CameraBoardSocket camera)
camera - Set the camera from whose perspective the disparity/depth will be aligned@Deprecated public void setConfidenceThreshold(int confThr)
confThr - Confidence threshold value 0..255public void setRectification(@Cast(value="bool") boolean enable)
public void setLeftRightCheck(@Cast(value="bool") boolean enable)
public void setSubpixel(@Cast(value="bool") boolean enable)
public void setSubpixelFractionalBits(int subpixelFractionalBits)
public void setExtendedDisparity(@Cast(value="bool") boolean enable)
public void setRectifyEdgeFillColor(int color)
color - Grayscale 0..255, or -1 to replicate pixels@Deprecated public void setRectifyMirrorFrame(@Cast(value="bool") boolean enable)
true.
The mirroring is required to have a normal non-mirrored disparity/depth output.
A side effect of this option is disparity alignment to the perspective of left or right input:
false: mapped to left and mirrored, true: mapped to right.
With LR-check enabled, this option is ignored, none of the outputs are mirrored,
and disparity is mapped to right.enable - True for normal disparity/depth, otherwise mirrored@Deprecated public void setOutputRectified(@Cast(value="bool") boolean enable)
@Deprecated public void setOutputDepth(@Cast(value="bool") boolean enable)
public void setRuntimeModeSwitch(@Cast(value="bool") boolean enable)
public void setNumFramesPool(int numFramesPool)
numFramesPool - How many frames should the pool have@Deprecated public float getMaxDisparity()
public void setPostProcessingHardwareResources(int numShaves,
int numMemorySlices)
numShaves - Number of shaves.numMemorySlices - Number of memory slices.public void setDefaultProfilePreset(StereoDepth.PresetMode mode)
mode - Stereo depth preset modepublic void setDefaultProfilePreset(@Cast(value="dai::node::StereoDepth::PresetMode") int mode)
@Deprecated public void setFocalLengthFromCalibration(@Cast(value="bool") boolean focalLengthFromCalibration)
public void useHomographyRectification(@Cast(value="bool") boolean useHomographyRectification)
useHomographyRectification - true: 3x3 homography matrix generated from calibration data is used for stereo rectification, can't correct lens
distortion.
false: sparse mesh is generated on-device from calibration data with mesh step specified with setMeshStep (Default: (16, 16)), can correct lens
distortion. Implementation for generating the mesh is same as opencv's initUndistortRectifyMap function. Only the first 8 distortion coefficients are
used from calibration data.public void enableDistortionCorrection(@Cast(value="bool") boolean enableDistortionCorrection)
public void setBaseline(float baseline)
public void setFocalLength(float focalLength)
public void setDisparityToDepthUseSpecTranslation(@Cast(value="bool") boolean specTranslation)
public void setRectificationUseSpecTranslation(@Cast(value="bool") boolean specTranslation)
public void setDepthAlignmentUseSpecTranslation(@Cast(value="bool") boolean specTranslation)
public void setAlphaScaling(float alpha)
Copyright © 2023. All rights reserved.