Program Listing for File StereoDepthProperties.hpp

Return to documentation for file (include/depthai/properties/StereoDepthProperties.hpp)

#pragma once

#include "depthai/common/CameraBoardSocket.hpp"
#include "depthai/common/EepromData.hpp"
#include "depthai/common/optional.hpp"
#include "depthai/pipeline/datatype/StereoDepthConfig.hpp"
#include "depthai/properties/Properties.hpp"

namespace dai {

struct StereoDepthProperties : PropertiesSerializable<Properties, StereoDepthProperties> {
    static constexpr const std::int32_t AUTO = -1;

    struct RectificationMesh {
        std::string meshLeftUri;
        std::string meshRightUri;
        std::optional<std::uint32_t> meshSize;
        uint16_t stepWidth = 16;
        uint16_t stepHeight = 16;

        DEPTHAI_SERIALIZE(RectificationMesh, meshLeftUri, meshRightUri, meshSize, stepWidth, stepHeight);
    };

    StereoDepthConfig initialConfig;

    using MedianFilter = dai::StereoDepthConfig::MedianFilter;

    using DepthAlign = dai::StereoDepthConfig::AlgorithmControl::DepthAlign;

    CameraBoardSocket depthAlignCamera = CameraBoardSocket::AUTO;

    bool enableRectification = true;

    std::int32_t rectifyEdgeFillColor = 0;
    std::optional<std::int32_t> width;
    std::optional<std::int32_t> height;
    std::optional<std::int32_t> outWidth;
    std::optional<std::int32_t> outHeight;
    bool outKeepAspectRatio = true;

    RectificationMesh mesh;

    bool enableRuntimeStereoModeSwitch = false;

    int numFramesPool = 3;

    std::int32_t numPostProcessingShaves = AUTO;

    std::int32_t numPostProcessingMemorySlices = AUTO;

    bool focalLengthFromCalibration = true;

    std::optional<bool> useHomographyRectification;

    bool enableFrameSync = true;

    /*
     * Override baseline from calibration.
     * Used only in disparity to depth conversion.
     * Units are centimeters.
     */
    std::optional<float> baseline;

    std::optional<float> focalLength;

    std::optional<bool> disparityToDepthUseSpecTranslation = std::nullopt;

    std::optional<bool> rectificationUseSpecTranslation = std::nullopt;

    std::optional<bool> depthAlignmentUseSpecTranslation = std::nullopt;

    std::optional<float> alphaScaling;

    ~StereoDepthProperties() override;
};

DEPTHAI_SERIALIZE_EXT(StereoDepthProperties,
                      initialConfig,
                      depthAlignCamera,
                      enableRectification,
                      rectifyEdgeFillColor,
                      width,
                      height,
                      outWidth,
                      outHeight,
                      outKeepAspectRatio,
                      mesh,
                      enableRuntimeStereoModeSwitch,
                      numFramesPool,
                      numPostProcessingShaves,
                      numPostProcessingMemorySlices,
                      focalLengthFromCalibration,
                      useHomographyRectification,
                      enableFrameSync,
                      baseline,
                      focalLength,
                      disparityToDepthUseSpecTranslation,
                      rectificationUseSpecTranslation,
                      depthAlignmentUseSpecTranslation,
                      alphaScaling);
}  // namespace dai