# RGB & TinyYolo with spatial data

This example shows how to run Yolo on the RGB input frame, and how to display both the RGB preview, detections, depth map and
spatial information (X,Y,Z). It's similar to example [RGB & MobilenetSSD with spatial
data](https://docs.luxonis.com/software/depthai/examples/spatial_mobilenet.md) except it is running TinyYolo network. X,Y,Z
coordinates are relative to the center of depth map.

Configurable, network dependent parameters are required for correct decoding:

 * setNumClasses() - number of YOLO classes
 * setCoordinateSize() - size of coordinate
 * setAnchors() - yolo anchors
 * setAnchorMasks() - anchorMasks26, anchorMasks13 (anchorMasks52 - additionally for full YOLOv4)
 * setIouThreshold() - intersection over union threshold
 * setConfidenceThreshold() - confidence threshold above which objects are detected

### Similar samples:

 * [Spatial location calculator](https://docs.luxonis.com/software/depthai/examples/spatial_location_calculator.md)
 * [Spatial object tracker on RGB](https://docs.luxonis.com/software/depthai/examples/spatial_object_tracker.md)
 * [RGB & MobilenetSSD with spatial data](https://docs.luxonis.com/software/depthai/examples/spatial_mobilenet.md)
 * [Mono & MobilenetSSD with spatial data](https://docs.luxonis.com/software/depthai/examples/mono_depth_mobilenetssd.md)

## Demo

## Setup

This example requires the DepthAI v3 API, see [installation instructions](https://docs.luxonis.com/software-v3/depthai.md).

## Source code

#### Python

```python
#!/usr/bin/env python3

from pathlib import Path
import sys
import cv2
import depthai as dai
import numpy as np
import time

'''
Spatial Tiny-yolo example
  Performs inference on RGB camera and retrieves spatial location coordinates: x,y,z relative to the center of depth map.
  Can be used for tiny-yolo-v3 or tiny-yolo-v4 networks
'''

# Get argument first
nnBlobPath = str((Path(__file__).parent / Path('../models/yolo-v4-tiny-tf_openvino_2021.4_6shave.blob')).resolve().absolute())
if 1 < len(sys.argv):
    arg = sys.argv[1]
    if arg == "yolo3":
        nnBlobPath = str((Path(__file__).parent / Path('../models/yolo-v3-tiny-tf_openvino_2021.4_6shave.blob')).resolve().absolute())
    elif arg == "yolo4":
        nnBlobPath = str((Path(__file__).parent / Path('../models/yolo-v4-tiny-tf_openvino_2021.4_6shave.blob')).resolve().absolute())
    else:
        nnBlobPath = arg
else:
    print("Using Tiny YoloV4 model. If you wish to use Tiny YOLOv3, call 'tiny_yolo.py yolo3'")

if not Path(nnBlobPath).exists():
    import sys
    raise FileNotFoundError(f'Required file/s not found, please run "{sys.executable} install_requirements.py"')

# Tiny yolo v3/4 label texts
labelMap = [
    "person",         "bicycle",    "car",           "motorbike",     "aeroplane",   "bus",           "train",
    "truck",          "boat",       "traffic light", "fire hydrant",  "stop sign",   "parking meter", "bench",
    "bird",           "cat",        "dog",           "horse",         "sheep",       "cow",           "elephant",
    "bear",           "zebra",      "giraffe",       "backpack",      "umbrella",    "handbag",       "tie",
    "suitcase",       "frisbee",    "skis",          "snowboard",     "sports ball", "kite",          "baseball bat",
    "baseball glove", "skateboard", "surfboard",     "tennis racket", "bottle",      "wine glass",    "cup",
    "fork",           "knife",      "spoon",         "bowl",          "banana",      "apple",         "sandwich",
    "orange",         "broccoli",   "carrot",        "hot dog",       "pizza",       "donut",         "cake",
    "chair",          "sofa",       "pottedplant",   "bed",           "diningtable", "toilet",        "tvmonitor",
    "laptop",         "mouse",      "remote",        "keyboard",      "cell phone",  "microwave",     "oven",
    "toaster",        "sink",       "refrigerator",  "book",          "clock",       "vase",          "scissors",
    "teddy bear",     "hair drier", "toothbrush"
]

syncNN = True

# Create pipeline
pipeline = dai.Pipeline()

# Define sources and outputs
camRgb = pipeline.create(dai.node.ColorCamera)
spatialDetectionNetwork = pipeline.create(dai.node.YoloSpatialDetectionNetwork)
monoLeft = pipeline.create(dai.node.MonoCamera)
monoRight = pipeline.create(dai.node.MonoCamera)
stereo = pipeline.create(dai.node.StereoDepth)
nnNetworkOut = pipeline.create(dai.node.XLinkOut)

xoutRgb = pipeline.create(dai.node.XLinkOut)
xoutNN = pipeline.create(dai.node.XLinkOut)
xoutDepth = pipeline.create(dai.node.XLinkOut)

xoutRgb.setStreamName("rgb")
xoutNN.setStreamName("detections")
xoutDepth.setStreamName("depth")
nnNetworkOut.setStreamName("nnNetwork")

# Properties
camRgb.setPreviewSize(416, 416)
camRgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
camRgb.setInterleaved(False)
camRgb.setColorOrder(dai.ColorCameraProperties.ColorOrder.BGR)

monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoLeft.setCamera("left")
monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoRight.setCamera("right")

# setting node configs
stereo.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
# Align depth map to the perspective of RGB camera, on which inference is done
stereo.setDepthAlign(dai.CameraBoardSocket.CAM_A)
stereo.setOutputSize(monoLeft.getResolutionWidth(), monoLeft.getResolutionHeight())
stereo.setSubpixel(True)

spatialDetectionNetwork.setBlobPath(nnBlobPath)
spatialDetectionNetwork.setConfidenceThreshold(0.5)
spatialDetectionNetwork.input.setBlocking(False)
spatialDetectionNetwork.setBoundingBoxScaleFactor(0.5)
spatialDetectionNetwork.setDepthLowerThreshold(100)
spatialDetectionNetwork.setDepthUpperThreshold(5000)

# Yolo specific parameters
spatialDetectionNetwork.setNumClasses(80)
spatialDetectionNetwork.setCoordinateSize(4)
spatialDetectionNetwork.setAnchors([10,14, 23,27, 37,58, 81,82, 135,169, 344,319])
spatialDetectionNetwork.setAnchorMasks({ "side26": [1,2,3], "side13": [3,4,5] })
spatialDetectionNetwork.setIouThreshold(0.5)

# Linking
monoLeft.out.link(stereo.left)
monoRight.out.link(stereo.right)

camRgb.preview.link(spatialDetectionNetwork.input)
if syncNN:
    spatialDetectionNetwork.passthrough.link(xoutRgb.input)
else:
    camRgb.preview.link(xoutRgb.input)

spatialDetectionNetwork.out.link(xoutNN.input)

stereo.depth.link(spatialDetectionNetwork.inputDepth)
spatialDetectionNetwork.passthroughDepth.link(xoutDepth.input)
spatialDetectionNetwork.outNetwork.link(nnNetworkOut.input)

# Connect to device and start pipeline
with dai.Device(pipeline) as device:

    # Output queues will be used to get the rgb frames and nn data from the outputs defined above
    previewQueue = device.getOutputQueue(name="rgb", maxSize=4, blocking=False)
    detectionNNQueue = device.getOutputQueue(name="detections", maxSize=4, blocking=False)
    depthQueue = device.getOutputQueue(name="depth", maxSize=4, blocking=False)
    networkQueue = device.getOutputQueue(name="nnNetwork", maxSize=4, blocking=False)

    startTime = time.monotonic()
    counter = 0
    fps = 0
    color = (255, 255, 255)
    printOutputLayersOnce = True

    while True:
        inPreview = previewQueue.get()
        inDet = detectionNNQueue.get()
        depth = depthQueue.get()
        inNN = networkQueue.get()

        if printOutputLayersOnce:
            toPrint = 'Output layer names:'
            for ten in inNN.getAllLayerNames():
                toPrint = f'{toPrint} {ten},'
            print(toPrint)
            printOutputLayersOnce = False

        frame = inPreview.getCvFrame()
        depthFrame = depth.getFrame() # depthFrame values are in millimeters

        depth_downscaled = depthFrame[::4]
        if np.all(depth_downscaled == 0):
            min_depth = 0  # Set a default minimum depth value when all elements are zero
        else:
            min_depth = np.percentile(depth_downscaled[depth_downscaled != 0], 1)
        max_depth = np.percentile(depth_downscaled, 99)
        depthFrameColor = np.interp(depthFrame, (min_depth, max_depth), (0, 255)).astype(np.uint8)
        depthFrameColor = cv2.applyColorMap(depthFrameColor, cv2.COLORMAP_HOT)

        counter+=1
        current_time = time.monotonic()
        if (current_time - startTime) > 1 :
            fps = counter / (current_time - startTime)
            counter = 0
            startTime = current_time

        detections = inDet.detections

        # If the frame is available, draw bounding boxes on it and show the frame
        height = frame.shape[0]
        width  = frame.shape[1]
        for detection in detections:
            roiData = detection.boundingBoxMapping
            roi = roiData.roi
            roi = roi.denormalize(depthFrameColor.shape[1], depthFrameColor.shape[0])
            topLeft = roi.topLeft()
            bottomRight = roi.bottomRight()
            xmin = int(topLeft.x)
            ymin = int(topLeft.y)
            xmax = int(bottomRight.x)
            ymax = int(bottomRight.y)
            cv2.rectangle(depthFrameColor, (xmin, ymin), (xmax, ymax), color, 1)

            # Denormalize bounding box
            x1 = int(detection.xmin * width)
            x2 = int(detection.xmax * width)
            y1 = int(detection.ymin * height)
            y2 = int(detection.ymax * height)
            try:
                label = labelMap[detection.label]
            except:
                label = detection.label
            cv2.putText(frame, str(label), (x1 + 10, y1 + 20), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255)
            cv2.putText(frame, "{:.2f}".format(detection.confidence*100), (x1 + 10, y1 + 35), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255)
            cv2.putText(frame, f"X: {int(detection.spatialCoordinates.x)} mm", (x1 + 10, y1 + 50), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255)
            cv2.putText(frame, f"Y: {int(detection.spatialCoordinates.y)} mm", (x1 + 10, y1 + 65), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255)
            cv2.putText(frame, f"Z: {int(detection.spatialCoordinates.z)} mm", (x1 + 10, y1 + 80), cv2.FONT_HERSHEY_TRIPLEX, 0.5, 255)

            cv2.rectangle(frame, (x1, y1), (x2, y2), color, cv2.FONT_HERSHEY_SIMPLEX)

        cv2.putText(frame, "NN fps: {:.2f}".format(fps), (2, frame.shape[0] - 4), cv2.FONT_HERSHEY_TRIPLEX, 0.4, color)
        cv2.imshow("depth", depthFrameColor)
        cv2.imshow("rgb", frame)

        if cv2.waitKey(1) == ord('q'):
            break
```

#### C++

```cpp
#include <chrono>

#include "utility.hpp"

// Includes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"

static const std::vector<std::string> labelMap = {
    "person",        "bicycle",      "car",           "motorbike",     "aeroplane",   "bus",         "train",       "truck",        "boat",
    "traffic light", "fire hydrant", "stop sign",     "parking meter", "bench",       "bird",        "cat",         "dog",          "horse",
    "sheep",         "cow",          "elephant",      "bear",          "zebra",       "giraffe",     "backpack",    "umbrella",     "handbag",
    "tie",           "suitcase",     "frisbee",       "skis",          "snowboard",   "sports ball", "kite",        "baseball bat", "baseball glove",
    "skateboard",    "surfboard",    "tennis racket", "bottle",        "wine glass",  "cup",         "fork",        "knife",        "spoon",
    "bowl",          "banana",       "apple",         "sandwich",      "orange",      "broccoli",    "carrot",      "hot dog",      "pizza",
    "donut",         "cake",         "chair",         "sofa",          "pottedplant", "bed",         "diningtable", "toilet",       "tvmonitor",
    "laptop",        "mouse",        "remote",        "keyboard",      "cell phone",  "microwave",   "oven",        "toaster",      "sink",
    "refrigerator",  "book",         "clock",         "vase",          "scissors",    "teddy bear",  "hair drier",  "toothbrush"};

static std::atomic<bool> syncNN{true};

int main(int argc, char** argv) {
    using namespace std;
    using namespace std::chrono;
    std::string nnPath(BLOB_PATH);

    // If path to blob specified, use that
    if(argc > 1) {
        nnPath = std::string(argv[1]);
    }

    // Print which blob we are using
    printf("Using blob at path: %s\n", nnPath.c_str());

    // Create pipeline
    dai::Pipeline pipeline;

    // Define sources and outputs
    auto camRgb = pipeline.create<dai::node::ColorCamera>();
    auto spatialDetectionNetwork = pipeline.create<dai::node::YoloSpatialDetectionNetwork>();
    auto monoLeft = pipeline.create<dai::node::MonoCamera>();
    auto monoRight = pipeline.create<dai::node::MonoCamera>();
    auto stereo = pipeline.create<dai::node::StereoDepth>();

    auto xoutRgb = pipeline.create<dai::node::XLinkOut>();
    auto xoutNN = pipeline.create<dai::node::XLinkOut>();
    auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
    auto nnNetworkOut = pipeline.create<dai::node::XLinkOut>();

    xoutRgb->setStreamName("rgb");
    xoutNN->setStreamName("detections");
    xoutDepth->setStreamName("depth");
    nnNetworkOut->setStreamName("nnNetwork");

    // Properties
    camRgb->setPreviewSize(416, 416);
    camRgb->setResolution(dai::ColorCameraProperties::SensorResolution::THE_1080_P);
    camRgb->setInterleaved(false);
    camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR);

    monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
    monoLeft->setCamera("left");
    monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
    monoRight->setCamera("right");

    // setting node configs
    stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
    // Align depth map to the perspective of RGB camera, on which inference is done
    stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A);
    stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight());

    spatialDetectionNetwork->setBlobPath(nnPath);
    spatialDetectionNetwork->setConfidenceThreshold(0.5f);
    spatialDetectionNetwork->input.setBlocking(false);
    spatialDetectionNetwork->setBoundingBoxScaleFactor(0.5);
    spatialDetectionNetwork->setDepthLowerThreshold(100);
    spatialDetectionNetwork->setDepthUpperThreshold(5000);

    // yolo specific parameters
    spatialDetectionNetwork->setNumClasses(80);
    spatialDetectionNetwork->setCoordinateSize(4);
    spatialDetectionNetwork->setAnchors({10, 14, 23, 27, 37, 58, 81, 82, 135, 169, 344, 319});
    spatialDetectionNetwork->setAnchorMasks({{"side26", {1, 2, 3}}, {"side13", {3, 4, 5}}});
    spatialDetectionNetwork->setIouThreshold(0.5f);

    // Linking
    monoLeft->out.link(stereo->left);
    monoRight->out.link(stereo->right);

    camRgb->preview.link(spatialDetectionNetwork->input);
    if(syncNN) {
        spatialDetectionNetwork->passthrough.link(xoutRgb->input);
    } else {
        camRgb->preview.link(xoutRgb->input);
    }

    spatialDetectionNetwork->out.link(xoutNN->input);

    stereo->depth.link(spatialDetectionNetwork->inputDepth);
    spatialDetectionNetwork->passthroughDepth.link(xoutDepth->input);
    spatialDetectionNetwork->outNetwork.link(nnNetworkOut->input);

    // Connect to device and start pipeline
    dai::Device device(pipeline);

    // Output queues will be used to get the rgb frames and nn data from the outputs defined above
    auto previewQueue = device.getOutputQueue("rgb", 4, false);
    auto detectionNNQueue = device.getOutputQueue("detections", 4, false);
    auto depthQueue = device.getOutputQueue("depth", 4, false);
    auto networkQueue = device.getOutputQueue("nnNetwork", 4, false);

    auto startTime = steady_clock::now();
    int counter = 0;
    float fps = 0;
    auto color = cv::Scalar(255, 255, 255);
    bool printOutputLayersOnce = true;

    while(true) {
        auto imgFrame = previewQueue->get<dai::ImgFrame>();
        auto inDet = detectionNNQueue->get<dai::SpatialImgDetections>();
        auto depth = depthQueue->get<dai::ImgFrame>();
        auto inNN = networkQueue->get<dai::NNData>();

        if(printOutputLayersOnce && inNN) {
            std::cout << "Output layer names: ";
            for(const auto& ten : inNN->getAllLayerNames()) {
                std::cout << ten << ", ";
            }
            std::cout << std::endl;
            printOutputLayersOnce = false;
        }

        cv::Mat frame = imgFrame->getCvFrame();
        cv::Mat depthFrame = depth->getFrame();  // depthFrame values are in millimeters

        cv::Mat depthFrameColor;
        cv::normalize(depthFrame, depthFrameColor, 255, 0, cv::NORM_INF, CV_8UC1);
        cv::equalizeHist(depthFrameColor, depthFrameColor);
        cv::applyColorMap(depthFrameColor, depthFrameColor, cv::COLORMAP_HOT);

        counter++;
        auto currentTime = steady_clock::now();
        auto elapsed = duration_cast<duration<float>>(currentTime - startTime);
        if(elapsed > seconds(1)) {
            fps = counter / elapsed.count();
            counter = 0;
            startTime = currentTime;
        }

        auto detections = inDet->detections;

        for(const auto& detection : detections) {
            auto roiData = detection.boundingBoxMapping;
            auto roi = roiData.roi;
            roi = roi.denormalize(depthFrameColor.cols, depthFrameColor.rows);
            auto topLeft = roi.topLeft();
            auto bottomRight = roi.bottomRight();
            auto xmin = (int)topLeft.x;
            auto ymin = (int)topLeft.y;
            auto xmax = (int)bottomRight.x;
            auto ymax = (int)bottomRight.y;
            cv::rectangle(depthFrameColor, cv::Rect(cv::Point(xmin, ymin), cv::Point(xmax, ymax)), color, cv::FONT_HERSHEY_SIMPLEX);

            int x1 = detection.xmin * frame.cols;
            int y1 = detection.ymin * frame.rows;
            int x2 = detection.xmax * frame.cols;
            int y2 = detection.ymax * frame.rows;

            uint32_t labelIndex = detection.label;
            std::string labelStr = to_string(labelIndex);
            if(labelIndex < labelMap.size()) {
                labelStr = labelMap[labelIndex];
            }
            cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
            std::stringstream confStr;
            confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
            cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 35), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);

            std::stringstream depthX;
            depthX << "X: " << (int)detection.spatialCoordinates.x << " mm";
            cv::putText(frame, depthX.str(), cv::Point(x1 + 10, y1 + 50), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
            std::stringstream depthY;
            depthY << "Y: " << (int)detection.spatialCoordinates.y << " mm";
            cv::putText(frame, depthY.str(), cv::Point(x1 + 10, y1 + 65), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
            std::stringstream depthZ;
            depthZ << "Z: " << (int)detection.spatialCoordinates.z << " mm";
            cv::putText(frame, depthZ.str(), cv::Point(x1 + 10, y1 + 80), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);

            cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
        }

        std::stringstream fpsStr;
        fpsStr << std::fixed << std::setprecision(2) << fps;
        cv::putText(frame, fpsStr.str(), cv::Point(2, imgFrame->getHeight() - 4), cv::FONT_HERSHEY_TRIPLEX, 0.4, color);

        cv::imshow("depth", depthFrameColor);
        cv::imshow("rgb", frame);

        int key = cv::waitKey(1);
        if(key == 'q' || key == 'Q') {
            return 0;
        }
    }
    return 0;
}
```

## Pipeline

### examples/spatial_tiny_yolo.pipeline.json

```json
{
  "pipeline": {
    "connections": [
      {
        "node1Id": 2,
        "node1Output": "out",
        "node1OutputGroup": "",
        "node2Id": 4,
        "node2Input": "left",
        "node2InputGroup": ""
      },
      {
        "node1Id": 3,
        "node1Output": "out",
        "node1OutputGroup": "",
        "node2Id": 4,
        "node2Input": "right",
        "node2InputGroup": ""
      },
      {
        "node1Id": 0,
        "node1Output": "preview",
        "node1OutputGroup": "",
        "node2Id": 1,
        "node2Input": "in",
        "node2InputGroup": ""
      },
      {
        "node1Id": 4,
        "node1Output": "depth",
        "node1OutputGroup": "",
        "node2Id": 1,
        "node2Input": "inputDepth",
        "node2InputGroup": ""
      },
      {
        "node1Id": 1,
        "node1Output": "passthrough",
        "node1OutputGroup": "",
        "node2Id": 6,
        "node2Input": "in",
        "node2InputGroup": ""
      },
      {
        "node1Id": 1,
        "node1Output": "out",
        "node1OutputGroup": "",
        "node2Id": 7,
        "node2Input": "in",
        "node2InputGroup": ""
      },
      {
        "node1Id": 1,
        "node1Output": "passthroughDepth",
        "node1OutputGroup": "",
        "node2Id": 8,
        "node2Input": "in",
        "node2InputGroup": ""
      },
      {
        "node1Id": 1,
        "node1Output": "outNetwork",
        "node1OutputGroup": "",
        "node2Id": 5,
        "node2Input": "in",
        "node2InputGroup": ""
      }
    ],
    "globalProperties": {
      "calibData": null,
      "cameraTuningBlobSize": null,
      "cameraTuningBlobUri": "",
      "leonCssFrequencyHz": 700000000.0,
      "leonMssFrequencyHz": 700000000.0,
      "pipelineName": null,
      "pipelineVersion": null,
      "sippBufferSize": 18432,
      "sippDmaBufferSize": 16384,
      "xlinkChunkSize": -1
    },
    "nodes": [
      [
        0,
        {
          "id": 0,
          "ioInfo": [
            [
              [
                "",
                "inputConfig"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 1,
                "name": "inputConfig",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "raw"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 6,
                "name": "raw",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "still"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 7,
                "name": "still",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "inputControl"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 2,
                "name": "inputControl",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "video"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 3,
                "name": "video",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "isp"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 4,
                "name": "isp",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "preview"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 5,
                "name": "preview",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "frameEvent"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 8,
                "name": "frameEvent",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ]
          ],
          "name": "ColorCamera",
          "properties": {
            "boardSocket": -1,
            "cameraName": "",
            "colorOrder": 0,
            "fp16": false,
            "fps": 30.0,
            "imageOrientation": -1,
            "initialControl": {
              "aeLockMode": false,
              "aeMaxExposureTimeUs": 0,
              "aeRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "afRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "antiBandingMode": 0,
              "autoFocusMode": 3,
              "awbLockMode": false,
              "awbMode": 0,
              "brightness": 0,
              "captureIntent": 0,
              "chromaDenoise": 0,
              "cmdMask": 0,
              "contrast": 0,
              "controlMode": 0,
              "effectMode": 0,
              "expCompensation": 0,
              "expManual": {
                "exposureTimeUs": 0,
                "frameDurationUs": 0,
                "sensitivityIso": 0
              },
              "frameSyncMode": 0,
              "lensPosAutoInfinity": 0,
              "lensPosAutoMacro": 0,
              "lensPosition": 0,
              "lensPositionRaw": 0.0,
              "lowPowerNumFramesBurst": 0,
              "lowPowerNumFramesDiscard": 0,
              "lumaDenoise": 0,
              "saturation": 0,
              "sceneMode": 0,
              "sharpness": 0,
              "strobeConfig": {
                "activeLevel": 0,
                "enable": 0,
                "gpioNumber": 0
              },
              "strobeTimings": {
                "durationUs": 0,
                "exposureBeginOffsetUs": 0,
                "exposureEndOffsetUs": 0
              },
              "wbColorTemp": 0
            },
            "interleaved": false,
            "isp3aFps": 0,
            "ispScale": {
              "horizDenominator": 0,
              "horizNumerator": 0,
              "vertDenominator": 0,
              "vertNumerator": 0
            },
            "numFramesPoolIsp": 3,
            "numFramesPoolPreview": 4,
            "numFramesPoolRaw": 3,
            "numFramesPoolStill": 4,
            "numFramesPoolVideo": 4,
            "previewHeight": 416,
            "previewKeepAspectRatio": true,
            "previewWidth": 416,
            "rawPacked": null,
            "resolution": 0,
            "sensorCropX": -1.0,
            "sensorCropY": -1.0,
            "stillHeight": -1,
            "stillWidth": -1,
            "videoHeight": -1,
            "videoWidth": -1
          }
        }
      ],
      [
        1,
        {
          "id": 1,
          "ioInfo": [
            [
              [
                "",
                "in"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 9,
                "name": "in",
                "queueSize": 5,
                "type": 3,
                "waitForMessage": true
              }
            ],
            [
              [
                "",
                "passthroughDepth"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 14,
                "name": "passthroughDepth",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "inputDepth"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 10,
                "name": "inputDepth",
                "queueSize": 4,
                "type": 3,
                "waitForMessage": true
              }
            ],
            [
              [
                "",
                "boundingBoxMapping"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 13,
                "name": "boundingBoxMapping",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "out"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 11,
                "name": "out",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "passthrough"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 12,
                "name": "passthrough",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ]
          ],
          "name": "SpatialDetectionNetwork",
          "properties": {
            "blobSize": 12168064,
            "blobUri": "asset:__blob",
            "calculationAlgorithm": 4,
            "depthThresholds": {
              "lowerThreshold": 100,
              "upperThreshold": 5000
            },
            "detectedBBScaleFactor": 0.5,
            "numFrames": 8,
            "numNCEPerThread": 0,
            "numThreads": 0,
            "parser": {
              "anchorMasks": {
                "side13": [
                  3,
                  4,
                  5
                ],
                "side26": [
                  1,
                  2,
                  3
                ]
              },
              "anchors": [
                10.0,
                14.0,
                23.0,
                27.0,
                37.0,
                58.0,
                81.0,
                82.0,
                135.0,
                169.0,
                344.0,
                319.0
              ],
              "classes": 80,
              "confidenceThreshold": 0.5,
              "coordinates": 4,
              "iouThreshold": 0.5,
              "nnFamily": 0
            },
            "stepSize": -1
          }
        }
      ],
      [
        2,
        {
          "id": 2,
          "ioInfo": [
            [
              [
                "",
                "inputControl"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 15,
                "name": "inputControl",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "out"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 16,
                "name": "out",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "raw"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 17,
                "name": "raw",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "frameEvent"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 18,
                "name": "frameEvent",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ]
          ],
          "name": "MonoCamera",
          "properties": {
            "boardSocket": -1,
            "cameraName": "left",
            "fps": 30.0,
            "imageOrientation": -1,
            "initialControl": {
              "aeLockMode": false,
              "aeMaxExposureTimeUs": 0,
              "aeRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "afRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "antiBandingMode": 0,
              "autoFocusMode": 3,
              "awbLockMode": false,
              "awbMode": 0,
              "brightness": 0,
              "captureIntent": 0,
              "chromaDenoise": 0,
              "cmdMask": 0,
              "contrast": 0,
              "controlMode": 0,
              "effectMode": 0,
              "expCompensation": 0,
              "expManual": {
                "exposureTimeUs": 0,
                "frameDurationUs": 0,
                "sensitivityIso": 0
              },
              "frameSyncMode": 0,
              "lensPosAutoInfinity": 0,
              "lensPosAutoMacro": 0,
              "lensPosition": 0,
              "lensPositionRaw": 0.0,
              "lowPowerNumFramesBurst": 0,
              "lowPowerNumFramesDiscard": 0,
              "lumaDenoise": 0,
              "saturation": 0,
              "sceneMode": 0,
              "sharpness": 0,
              "strobeConfig": {
                "activeLevel": 0,
                "enable": 0,
                "gpioNumber": 0
              },
              "strobeTimings": {
                "durationUs": 0,
                "exposureBeginOffsetUs": 0,
                "exposureEndOffsetUs": 0
              },
              "wbColorTemp": 0
            },
            "isp3aFps": 0,
            "numFramesPool": 3,
            "numFramesPoolRaw": 3,
            "rawPacked": null,
            "resolution": 2
          }
        }
      ],
      [
        3,
        {
          "id": 3,
          "ioInfo": [
            [
              [
                "",
                "inputControl"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 19,
                "name": "inputControl",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "out"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 20,
                "name": "out",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "raw"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 21,
                "name": "raw",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "frameEvent"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 22,
                "name": "frameEvent",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ]
          ],
          "name": "MonoCamera",
          "properties": {
            "boardSocket": -1,
            "cameraName": "right",
            "fps": 30.0,
            "imageOrientation": -1,
            "initialControl": {
              "aeLockMode": false,
              "aeMaxExposureTimeUs": 0,
              "aeRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "afRegion": {
                "height": 0,
                "priority": 0,
                "width": 0,
                "x": 0,
                "y": 0
              },
              "antiBandingMode": 0,
              "autoFocusMode": 3,
              "awbLockMode": false,
              "awbMode": 0,
              "brightness": 0,
              "captureIntent": 0,
              "chromaDenoise": 0,
              "cmdMask": 0,
              "contrast": 0,
              "controlMode": 0,
              "effectMode": 0,
              "expCompensation": 0,
              "expManual": {
                "exposureTimeUs": 0,
                "frameDurationUs": 0,
                "sensitivityIso": 0
              },
              "frameSyncMode": 0,
              "lensPosAutoInfinity": 0,
              "lensPosAutoMacro": 0,
              "lensPosition": 0,
              "lensPositionRaw": 0.0,
              "lowPowerNumFramesBurst": 0,
              "lowPowerNumFramesDiscard": 0,
              "lumaDenoise": 0,
              "saturation": 0,
              "sceneMode": 0,
              "sharpness": 0,
              "strobeConfig": {
                "activeLevel": 0,
                "enable": 0,
                "gpioNumber": 0
              },
              "strobeTimings": {
                "durationUs": 0,
                "exposureBeginOffsetUs": 0,
                "exposureEndOffsetUs": 0
              },
              "wbColorTemp": 0
            },
            "isp3aFps": 0,
            "numFramesPool": 3,
            "numFramesPoolRaw": 3,
            "rawPacked": null,
            "resolution": 2
          }
        }
      ],
      [
        4,
        {
          "id": 4,
          "ioInfo": [
            [
              [
                "",
                "inputConfig"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 23,
                "name": "inputConfig",
                "queueSize": 4,
                "type": 3,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "left"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 24,
                "name": "left",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ],
            [
              [
                "",
                "debugExtDispLrCheckIt1"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 36,
                "name": "debugExtDispLrCheckIt1",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "right"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 25,
                "name": "right",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ],
            [
              [
                "",
                "syncedLeft"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 26,
                "name": "syncedLeft",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "depth"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 27,
                "name": "depth",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "disparity"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 28,
                "name": "disparity",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "syncedRight"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 29,
                "name": "syncedRight",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "debugDispCostDump"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 34,
                "name": "debugDispCostDump",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "debugDispLrCheckIt2"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 35,
                "name": "debugDispLrCheckIt2",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "rectifiedLeft"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 30,
                "name": "rectifiedLeft",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "debugExtDispLrCheckIt2"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 37,
                "name": "debugExtDispLrCheckIt2",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "rectifiedRight"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 31,
                "name": "rectifiedRight",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "confidenceMap"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 38,
                "name": "confidenceMap",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "outConfig"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 32,
                "name": "outConfig",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ],
            [
              [
                "",
                "debugDispLrCheckIt1"
              ],
              {
                "blocking": false,
                "group": "",
                "id": 33,
                "name": "debugDispLrCheckIt1",
                "queueSize": 8,
                "type": 0,
                "waitForMessage": false
              }
            ]
          ],
          "name": "StereoDepth",
          "properties": {
            "alphaScaling": null,
            "baseline": null,
            "depthAlignCamera": 0,
            "depthAlignmentUseSpecTranslation": null,
            "disparityToDepthUseSpecTranslation": null,
            "enableRectification": true,
            "enableRuntimeStereoModeSwitch": false,
            "focalLength": null,
            "focalLengthFromCalibration": true,
            "height": null,
            "initialConfig": {
              "algorithmControl": {
                "centerAlignmentShiftFactor": null,
                "customDepthUnitMultiplier": 1000.0,
                "depthAlign": 0,
                "depthUnit": 2,
                "disparityShift": 0,
                "enableExtended": false,
                "enableLeftRightCheck": true,
                "enableSubpixel": true,
                "leftRightCheckThreshold": 10,
                "numInvalidateEdgePixels": 0,
                "subpixelFractionalBits": 3
              },
              "censusTransform": {
                "enableMeanMode": true,
                "kernelMask": 0,
                "kernelSize": -1,
                "threshold": 0
              },
              "costAggregation": {
                "divisionFactor": 1,
                "horizontalPenaltyCostP1": 250,
                "horizontalPenaltyCostP2": 500,
                "verticalPenaltyCostP1": 250,
                "verticalPenaltyCostP2": 500
              },
              "costMatching": {
                "confidenceThreshold": 245,
                "disparityWidth": 1,
                "enableCompanding": false,
                "invalidDisparityValue": 0,
                "linearEquationParameters": {
                  "alpha": 0,
                  "beta": 2,
                  "threshold": 127
                }
              },
              "postProcessing": {
                "bilateralSigmaValue": 0,
                "brightnessFilter": {
                  "maxBrightness": 256,
                  "minBrightness": 0
                },
                "decimationFilter": {
                  "decimationFactor": 1,
                  "decimationMode": 0
                },
                "median": 5,
                "spatialFilter": {
                  "alpha": 0.5,
                  "delta": 0,
                  "enable": false,
                  "holeFillingRadius": 2,
                  "numIterations": 1
                },
                "speckleFilter": {
                  "enable": false,
                  "speckleRange": 50
                },
                "temporalFilter": {
                  "alpha": 0.4000000059604645,
                  "delta": 0,
                  "enable": false,
                  "persistencyMode": 3
                },
                "thresholdFilter": {
                  "maxRange": 65535,
                  "minRange": 0
                }
              }
            },
            "mesh": {
              "meshLeftUri": "",
              "meshRightUri": "",
              "meshSize": null,
              "stepHeight": 16,
              "stepWidth": 16
            },
            "numFramesPool": 3,
            "numPostProcessingMemorySlices": -1,
            "numPostProcessingShaves": -1,
            "outHeight": 400,
            "outKeepAspectRatio": true,
            "outWidth": 640,
            "rectificationUseSpecTranslation": null,
            "rectifyEdgeFillColor": 0,
            "useHomographyRectification": null,
            "width": null
          }
        }
      ],
      [
        5,
        {
          "id": 5,
          "ioInfo": [
            [
              [
                "",
                "in"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 39,
                "name": "in",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ]
          ],
          "name": "XLinkOut",
          "properties": {
            "maxFpsLimit": -1.0,
            "metadataOnly": false,
            "streamName": "nnNetwork"
          }
        }
      ],
      [
        6,
        {
          "id": 6,
          "ioInfo": [
            [
              [
                "",
                "in"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 40,
                "name": "in",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ]
          ],
          "name": "XLinkOut",
          "properties": {
            "maxFpsLimit": -1.0,
            "metadataOnly": false,
            "streamName": "rgb"
          }
        }
      ],
      [
        7,
        {
          "id": 7,
          "ioInfo": [
            [
              [
                "",
                "in"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 41,
                "name": "in",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ]
          ],
          "name": "XLinkOut",
          "properties": {
            "maxFpsLimit": -1.0,
            "metadataOnly": false,
            "streamName": "detections"
          }
        }
      ],
      [
        8,
        {
          "id": 8,
          "ioInfo": [
            [
              [
                "",
                "in"
              ],
              {
                "blocking": true,
                "group": "",
                "id": 42,
                "name": "in",
                "queueSize": 8,
                "type": 3,
                "waitForMessage": true
              }
            ]
          ],
          "name": "XLinkOut",
          "properties": {
            "maxFpsLimit": -1.0,
            "metadataOnly": false,
            "streamName": "depth"
          }
        }
      ]
    ]
  }
}
```

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
