C++ API Reference

namespace dai

Enums

enum CameraBoardSocket

Which Camera socket to use.

AUTO denotes that the decision will be made by device

Values:

enumerator AUTO
enumerator RGB
enumerator LEFT
enumerator RIGHT
enum CameraImageOrientation

Camera sensor image orientation / pixel readout. This exposes direct sensor settings. 90 or 270 degrees rotation is not available.

AUTO denotes that the decision will be made by device (e.g. on OAK-1/megaAI: ROTATE_180_DEG).

Values:

enumerator AUTO
enumerator NORMAL
enumerator HORIZONTAL_MIRROR
enumerator VERTICAL_FLIP
enumerator ROTATE_180_DEG
enum ProcessorType

On which processor the node will be placed

Enum specifying processor

Values:

enumerator LOS
enumerator LRT
enum DatatypeEnum

Values:

enumerator Buffer
enumerator ImgFrame
enumerator NNData
enumerator ImageManipConfig
enumerator CameraControl
enumerator ImgDetections
enumerator SpatialImgDetections
enumerator SystemInformation
enumerator SpatialLocationCalculatorConfig
enumerator SpatialLocationCalculatorData
enumerator Tracklets
enum LogLevel

Values:

enumerator TRACE
enumerator DEBUG
enumerator INFO
enumerator WARN
enumerator ERR
enumerator CRITICAL
enumerator OFF
enum TrackerType

Values:

enumerator ZERO_TERM_IMAGELESS
enumerator ZERO_TERM_COLOR_HISTOGRAM
enum TrackerIdAssigmentPolicy

Values:

enumerator UNIQUE_ID
enumerator SMALLEST_ID

Functions

std::ostream &operator<<(std::ostream &out, const Tracklet::TrackingStatus &status)
bool initialize(std::string additionalInfo = "")
bool isDatatypeSubclassOf(DatatypeEnum parent, DatatypeEnum children)

Variables

constexpr const char *LOG_DEFAULT_PATTERN = "[%E.%e] [%n] [%^%l%$] %v"
class ADatatype
#include <ADatatype.hpp>

Abstract message.

Subclassed by dai::Buffer

struct Asset
#include <AssetManager.hpp>

Asset is identified with string key and can store arbitrary binary data.

class AssetManager
#include <AssetManager.hpp>

AssetManager can store assets and serialize.

Public Functions

void addExisting(std::vector<std::shared_ptr<Asset>> assets)

Adds all assets in an array to the AssetManager

Parameters
  • assets: Vector of assets to add

void add(Asset asset)

Adds an asset object to AssetManager.

Parameters

void add(const std::string &key, Asset asset)

Adds an asset object to AssetManager with a specificied key. Key value will be assigned to an Asset as well

If asset with key already exists, the function throws an error

Parameters
  • key: Key under which the asset should be stored

  • asset: Asset to store

void set(const std::string &key, Asset asset)

Adds or overwrites existing asset with a specificied key.

Parameters
  • key: Key under which the asset should be stored

  • asset: Asset to store

std::shared_ptr<const Asset> get(const std::string &key) const

Return

Asset assigned to the specified key or throws an error otherwise

std::shared_ptr<Asset> get(const std::string &key)

Return

Asset assigned to the specified key or throws an error otherwise

std::vector<std::shared_ptr<const Asset>> getAll() const

Return

All asset stored in the AssetManager

std::vector<std::shared_ptr<Asset>> getAll()

Return

All asset stored in the AssetManager

std::size_t size() const

Return

Number of asset stored in the AssetManager

void remove(const std::string &key)

Removes asset with key

Parameters
  • key: Key of asset to remove

void serialize(Assets &serAssets, std::vector<std::uint8_t> &assetStorage) const

Serializes.

class Assets

Subclassed by dai::AssetsMutable

class AssetsMutable : public dai::Assets
struct AssetView
class Buffer : public dai::ADatatype
#include <Buffer.hpp>

Base message - buffer of binary data.

Subclassed by dai::CameraControl, dai::ImageManipConfig, dai::ImgDetections, dai::ImgFrame, dai::NNData, dai::SpatialImgDetections, dai::SpatialLocationCalculatorConfig, dai::SpatialLocationCalculatorData, dai::SystemInformation, dai::Tracklets

Public Functions

Buffer()

Creates Buffer message.

std::vector<std::uint8_t> &getData()

Return

Reference to internal buffer

void setData(std::vector<std::uint8_t> data)

Parameters
  • data: Copies data to internal buffer

class CallbackHandler
class CameraControl : public dai::Buffer
#include <CameraControl.hpp>

CameraControl message Specifies various camera control commands like:

  • Still capture

  • Auto focus

  • Anti banding

  • Auto white balance

  • Scene

  • Effect

Public Functions

CameraControl()

Construct CameraControl message.

void setCaptureStill(bool capture)

Set a command to capture a still image

void setStartStreaming()

Set a command to start streaming

void setStopStreaming()

Set a command to stop streaming

void setAutoFocusMode(AutoFocusMode mode)

Set a command to specify autofocus mode

void setAutoFocusTrigger()

Set a command to trigger autofocus

void setAutoFocusRegion(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height)

Set a command to specify focus region in pixels

Parameters
  • startX: X coordinate of top left corner of region

  • startY: Y coordinate of top left corner of region

  • width: Region width

  • height: Region height

void setManualFocus(uint8_t lensPosition)

Set a command to specify manual focus position

Parameters
  • lensPosition: specify lens position 0..255

void setAutoExposureEnable()

Set a command to enable auto exposure

void setAutoExposureLock(bool lock)

Set a command to specify lock auto exposure

Parameters
  • lock: Auto exposure lock mode enabled or disabled

void setAutoExposureRegion(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height)

Set a command to specify auto exposure region in pixels

Parameters
  • startX: X coordinate of top left corner of region

  • startY: Y coordinate of top left corner of region

  • width: Region width

  • height: Region height

void setAutoExposureCompensation(int compensation)

Set a command to specify auto exposure compensation

Parameters
  • compensation: Compensation value between -9..9

void setAntiBandingMode(AntiBandingMode mode)

Set a command to specify auto banding mode

Parameters
  • mode: Auto banding mode to use

void setManualExposure(uint32_t exposureTimeUs, uint32_t sensitivityIso)

Set a command to manually specify exposure

Parameters
  • exposureTimeUs: Exposure time in microseconds

  • sensitivityIso: Sensitivity as ISO value, usual range 100..1600

void setAutoWhiteBalanceMode(AutoWhiteBalanceMode mode)

Set a command to specify auto white balance mode

Parameters
  • mode: Auto white balance mode to use

void setAutoWhiteBalanceLock(bool lock)

Set a command to specify auto white balance lock

Parameters
  • lock: Auto white balance lock mode enabled or disabled

void setBrightness(int value)

Set a command to adjust image brightness

Parameters
  • value: Brightness, range -10..10

void setContrast(int value)

Set a command to adjust image contrast

Parameters
  • value: Contrast, range -10..10

void setSaturation(int value)

Set a command to adjust image saturation

Parameters
  • value: Saturation, range -10..10

void setSharpness(int value)

Set a command to adjust image sharpness

Parameters
  • value: Sharpness, range 0..4

void setLumaDenoise(int value)

Set a command to adjust luma denoise amount

Parameters
  • value: Luma denoise amount, range 0..4

void setChromaDenoise(int value)

Set a command to adjust chroma denoise amount

Parameters
  • value: Chroma denoise amount, range 0..4

void setSceneMode(SceneMode mode)

Set a command to specify scene mode

Parameters
  • mode: Scene mode

void setEffectMode(EffectMode mode)

Set a command to specify effect mode

Parameters
  • mode: Effect mode

bool getCaptureStill() const

Check whether command to capture a still is set

Return

True if capture still command is set

struct ChipTemperature
#include <ChipTemperature.hpp>

Chip temperature information.

Multiple temperature measurement points and their average

Public Members

float css

CPU Subsystem.

float mss

Media Subsystem.

float upa

Shave Array.

float dss

DRAM Subsystem.

float average

Average of measurements.

struct ColorCameraProperties
#include <ColorCameraProperties.hpp>

Specify ColorCamera options such as camera ID, …

Public Types

enum SensorResolution

Select the camera sensor resolution

Values:

enumerator THE_1080_P
enumerator THE_4_K
enumerator THE_12_MP
enum ColorOrder

For 24 bit color these can be either RGB or BGR

Values:

enumerator BGR
enumerator RGB

Public Members

CameraBoardSocket boardSocket = CameraBoardSocket::AUTO

Which socket will color camera use

CameraImageOrientation imageOrientation = CameraImageOrientation::AUTO

Camera sensor image orientation / pixel readout

ColorOrder colorOrder = ColorOrder::BGR

For 24 bit color these can be either RGB or BGR

bool interleaved = true

Are colors interleaved (R1G1B1, R2G2B2, …) or planar (R1R2…, G1G2…, B1B2)

bool fp16 = false

Are values FP16 type (0.0 - 255.0)

uint32_t previewHeight = 300

Preview frame output height

uint32_t previewWidth = 300

Preview frame output width

int32_t videoWidth = AUTO

Preview frame output width

int32_t videoHeight = AUTO

Preview frame output height

int32_t stillWidth = AUTO

Preview frame output width

int32_t stillHeight = AUTO

Preview frame output height

SensorResolution resolution = SensorResolution::THE_1080_P

Select the camera sensor resolution

float fps = 30.0

Camera sensor FPS

float sensorCropX = AUTO

Initial sensor crop, -1 signifies center crop

bool inputConfigSync = false

Whether to wait for config at ‘inputConfig’ io

bool previewKeepAspectRatio = true

Whether to keep aspect ratio of input (video size) or not

IspScale ispScale

Configure scaling for isp output.

struct IspScale
struct CpuUsage
#include <CpuUsage.hpp>

CpuUsage structure

Average usage in percent and time span of the average (since last query)

Public Members

float average

Average CPU usage, expressed with a normalized value (0-1)

int32_t msTime

Time span in which the average was calculated in milliseconds.

class DataInputQueue
#include <DataQueue.hpp>

Access to send messages through XLink stream

Public Functions

void setMaxDataSize(std::size_t maxSize)

Sets maximum message size. If message is larger than specified, then an exception is issued.

Parameters
  • maxSize: Maximum message size to add to queue

std::size_t getMaxDataSize()

Gets maximum queue size.

Return

Maximum message size

void setBlocking(bool blocking)

Sets queue behavior when full (maxSize)

Parameters
  • blocking: Specifies if block or overwrite the oldest message in the queue

bool getBlocking() const

Gets current queue behavior when full (maxSize)

Return

True if blocking, false otherwise

void setMaxSize(unsigned int maxSize)

Sets queue maximum size

Parameters
  • maxSize: Specifies maximum number of messages in the queue

unsigned int getMaxSize(unsigned int maxSize) const

Gets queue maximum size

Return

Maximum queue size

std::string getName() const

Gets queues name

Return

Queue name

void send(const std::shared_ptr<RawBuffer> &rawMsg)

Adds a raw message to the queue, which will be picked up and sent to the device. Can either block if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • rawMsg: Message to add to the queue

void send(const std::shared_ptr<ADatatype> &msg)

Adds a message to the queue, which will be picked up and sent to the device. Can either block if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • msg: Message to add to the queue

void send(const ADatatype &msg)

Adds a message to the queue, which will be picked up and sent to the device. Can either block if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • msg: Message to add to the queue

bool send(const std::shared_ptr<RawBuffer> &rawMsg, std::chrono::milliseconds timeout)

Adds message to the queue, which will be picked up and sent to the device. Can either block until timeout if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • rawMsg: Message to add to the queue

  • timeout: Maximum duration to block in milliseconds

bool send(const std::shared_ptr<ADatatype> &msg, std::chrono::milliseconds timeout)

Adds message to the queue, which will be picked up and sent to the device. Can either block until timeout if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • msg: Message to add to the queue

  • timeout: Maximum duration to block in milliseconds

bool send(const ADatatype &msg, std::chrono::milliseconds timeout)

Adds message to the queue, which will be picked up and sent to the device. Can either block until timeout if ‘blocking’ behavior is true or overwrite oldest

Parameters
  • msg: Message to add to the queue

  • timeout: Maximum duration to block in milliseconds

class DataOutputQueue
#include <DataQueue.hpp>

Access to receive messages coming from XLink stream

Public Types

using CallbackId = int

Alias for callback id.

Public Functions

void setBlocking(bool blocking)

Sets queue behavior when full (maxSize)

Parameters
  • blocking: Specifies if block or overwrite the oldest message in the queue

bool getBlocking() const

Gets current queue behavior when full (maxSize)

Return

True if blocking, false otherwise

void setMaxSize(unsigned int maxSize)

Sets queue maximum size

Parameters
  • maxSize: Specifies maximum number of messages in the queue

unsigned int getMaxSize(unsigned int maxSize) const

Gets queue maximum size

Return

Maximum queue size

std::string getName() const

Gets queues name

Return

Queue name

CallbackId addCallback(std::function<void(std::string, std::shared_ptr<ADatatype>)>)

Adds a callback on message received

Return

Callback id

Parameters
  • callback: Callback function with queue name and message pointer

CallbackId addCallback(std::function<void(std::shared_ptr<ADatatype>)>)

Adds a callback on message received

Return

Callback id

Parameters
  • callback: Callback function with message pointer

CallbackId addCallback(std::function<void()> callback)

Adds a callback on message received

Return

Callback id

Parameters
  • callback: Callback function without any parameters

bool removeCallback(CallbackId callbackId)

Removes a callback

Return

True if callback was removed, false otherwise

Parameters
  • callbackId: Id of callback to be removed

template<class T>
bool has()

Check whether front of the queue has message of type T

Return

True if queue isn’t empty and the first element is of type T, false otherwise

bool has()

Check whether front of the queue has a message (isn’t empty)

Return

True if queue isn’t empty, false otherwise

template<class T>
std::shared_ptr<T> tryGet()

Try to retrieve message T from queue. If message isn’t of type T it returns nullptr

Return

Message of type T or nullptr if no message available

std::shared_ptr<ADatatype> tryGet()

Try to retrieve message from queue. If no message available, return immidiately with nullptr

Return

Message or nullptr if no message available

template<class T>
std::shared_ptr<T> get()

Block until a message is available.

Return

Message of type T or nullptr if no message available

std::shared_ptr<ADatatype> get()

Block until a message is available.

Return

Message or nullptr if no message available

template<class T>
std::shared_ptr<T> front()

Gets first message in the queue.

Return

Message of type T or nullptr if no message available

std::shared_ptr<ADatatype> front()

Gets first message in the queue.

Return

Message or nullptr if no message available

template<class T, typename Rep, typename Period>
std::shared_ptr<T> get(std::chrono::duration<Rep, Period> timeout, bool &hasTimedout)

Block until a message is available with a timeout.

Return

Message of type T otherwise nullptr if message isn’t type T or timeout occured

Parameters
  • timeout: Duration for which the function should block

  • [out] hasTimedout: Outputs true if timeout occured, false otherwise

template<typename Rep, typename Period>
std::shared_ptr<ADatatype> get(std::chrono::duration<Rep, Period> timeout, bool &hasTimedout)

Block until a message is available with a timeout.

Return

Message of type T otherwise nullptr if message isn’t type T or timeout occured

Parameters
  • timeout: Duration for which the function should block

  • [out] hasTimedout: Outputs true if timeout occured, false otherwise

template<class T>
std::vector<std::shared_ptr<T>> tryGetAll()

Try to retrieve all messages in the queue.

Return

Vector of messages which can either be of type T or nullptr

std::vector<std::shared_ptr<ADatatype>> tryGetAll()

Try to retrieve all messages in the queue.

Return

Vector of messages

template<class T>
std::vector<std::shared_ptr<T>> getAll()

Block until at least one message in the queue. Then return all messages from the queue.

Return

Vector of messages which can either be of type T or nullptr

std::vector<std::shared_ptr<ADatatype>> getAll()

Block until at least one message in the queue. Then return all messages from the queue.

Return

Vector of messages

template<class T, typename Rep, typename Period>
std::vector<std::shared_ptr<T>> getAll(std::chrono::duration<Rep, Period> timeout, bool &hasTimedout)

Block for maximum timeout duration. Then return all messages from the queue.

Return

Vector of messages which can either be of type T or nullptr

Parameters
  • timeout: Maximum duration to block

  • [out] hasTimedout: Outputs true if timeout occured, false otherwise

template<typename Rep, typename Period>
std::vector<std::shared_ptr<ADatatype>> getAll(std::chrono::duration<Rep, Period> timeout, bool &hasTimedout)

Block for maximum timeout duration. Then return all messages from the queue.

Return

Vector of messages

Parameters
  • timeout: Maximum duration to block

  • [out] hasTimedout: Outputs true if timeout occured, false otherwise

struct DetectionNetworkProperties : public dai::NeuralNetworkProperties
#include <DetectionNetworkProperties.hpp>

Properties for DetectionNetwork

Subclassed by dai::SpatialDetectionNetworkProperties

Public Members

DetectionNetworkType nnFamily

Generic Neural Network properties.

int classes

YOLO specific network properties.

class Device
#include <Device.hpp>

Represents the DepthAI device with the methods to interact with it.

Public Functions

Device(const Pipeline &pipeline)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • pipeline: Pipeline to be executed on the device

Device(const Pipeline &pipeline, bool usb2Mode)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • pipeline: Pipeline to be executed on the device

  • usb2Mode: Boot device using USB2 mode firmware

Device(const Pipeline &pipeline, const char *pathToCmd)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • pipeline: Pipeline to be executed on the device

  • pathToCmd: Path to custom device firmware

Device(const Pipeline &pipeline, const std::string &pathToCmd)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • pipeline: Pipeline to be executed on the device

  • pathToCmd: Path to custom device firmware

Device(const Pipeline &pipeline, const DeviceInfo &devInfo, bool usb2Mode = false)

Connects to device specified by devInfo.

Parameters
  • pipeline: Pipeline to be executed on the device

  • devInfo: DeviceInfo which specifies which device to connect to

  • usb2Mode: Boot device using USB2 mode firmware

Device(const Pipeline &pipeline, const DeviceInfo &devInfo, const char *pathToCmd)

Connects to device specified by devInfo.

Parameters
  • pipeline: Pipeline to be executed on the device

  • devInfo: DeviceInfo which specifies which device to connect to

  • pathToCmd: Path to custom device firmware

Device(const Pipeline &pipeline, const DeviceInfo &devInfo, const std::string &pathToCmd)

Connects to device specified by devInfo.

Parameters
  • pipeline: Pipeline to be executed on the device

  • devInfo: DeviceInfo which specifies which device to connect to

  • usb2Mode: Path to custom device firmware

Device(OpenVINO::Version version = Pipeline::DEFAULT_OPENVINO_VERSION)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters

Device(OpenVINO::Version version, bool usb2Mode)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • version: OpenVINO version which the device will be booted with

  • usb2Mode: Boot device using USB2 mode firmware

Device(OpenVINO::Version version, const char *pathToCmd)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • version: OpenVINO version which the device will be booted with

  • pathToCmd: Path to custom device firmware

Device(OpenVINO::Version version, const std::string &pathToCmd)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
  • version: OpenVINO version which the device will be booted with

  • pathToCmd: Path to custom device firmware

Device(OpenVINO::Version version, const DeviceInfo &devInfo, bool usb2Mode = false)

Connects to device specified by devInfo.

Parameters
  • version: OpenVINO version which the device will be booted with

  • devInfo: DeviceInfo which specifies which device to connect to

  • usb2Mode: Boot device using USB2 mode firmware

Device(OpenVINO::Version version, const DeviceInfo &devInfo, const char *pathToCmd)

Connects to device specified by devInfo.

Parameters
  • version: OpenVINO version which the device will be booted with

  • devInfo: DeviceInfo which specifies which device to connect to

  • pathToCmd: Path to custom device firmware

Device(OpenVINO::Version version, const DeviceInfo &devInfo, const std::string &pathToCmd)

Connects to device specified by devInfo.

Parameters
  • version: OpenVINO version which the device will be booted with

  • devInfo: DeviceInfo which specifies which device to connect to

  • usb2Mode: Path to custom device firmware

~Device()

Device destructor. Closes the connection and data queues.

bool isPipelineRunning()

Checks if devices pipeline is already running

Return

True if running, false otherwise

bool startPipeline()

Starts the execution of the devices pipeline

Return

True if pipeline started, false otherwise

bool startPipeline(const Pipeline &pipeline)

Starts the execution of a given pipeline

Return

True if pipeline started, false otherwise

Parameters
  • pipeline: OpenVINO version of the pipeline must match the one which the device was booted with.

void setLogLevel(LogLevel level)

Sets the devices logging severity level. This level affects which logs are transfered from device to host.

Parameters
  • level: Logging severity

LogLevel getLogLevel()

Gets current logging severity level of the device.

Return

Logging severity level

void setLogOutputLevel(LogLevel level)

Sets logging level which decides printing level to standard output. If lower than setLogLevel, no messages will be printed

Parameters
  • level: Standard output printing severity

LogLevel getLogOutputLevel()

Gets logging level which decides printing level to standard output.

Return

Standard output printing severity

int addLogCallback(std::function<void(LogMessage)> callback)

Add a callback for device logging. The callback will be called from a separate thread with the LogMessage being passed.

Return

Id which can be used to later remove the callback

Parameters
  • callback: Callback to call whenever a log message arrives

bool removeLogCallback(int callbackId)

Removes a callback

Return

True if callback was removed, false otherwise

Parameters
  • callbackId: Id of callback to be removed

void setSystemInformationLoggingRate(float rateHz)

Sets rate of system information logging (“info” severity). Default 1Hz If parameter is less or equal to zero, then system information logging will be disabled

Parameters
  • rateHz: Logging rate in Hz

float getSystemInformationLoggingRate()

Gets current rate of system information logging (“info” severity) in Hz.

Return

Logging rate in Hz

std::shared_ptr<DataOutputQueue> getOutputQueue(const std::string &name)

Gets an output queue corresponding to stream name. If it doesn’t exist it throws

Return

Smart pointer to DataOutputQueue

Parameters
  • name: Queue/stream name, created by XLinkOut node

std::shared_ptr<DataOutputQueue> getOutputQueue(const std::string &name, unsigned int maxSize, bool blocking = true)

Gets a queue corresponding to stream name, if it exists, otherwise it throws. Also sets queue options

Return

Smart pointer to DataOutputQueue

Parameters
  • name: Queue/stream name, set in XLinkOut node

  • maxSize: Maximum number of messages in queue

  • blocking: Queue behavior once full. True specifies blocking and false overwriting of oldest messages. Default: true

std::vector<std::string> getOutputQueueNames() const

Get all available output queue names

Return

Vector of output queue names

std::shared_ptr<DataInputQueue> getInputQueue(const std::string &name)

Gets an input queue corresponding to stream name. If it doesn’t exist it throws

Return

Smart pointer to DataInputQueue

Parameters
  • name: Queue/stream name, set in XLinkIn node

std::shared_ptr<DataInputQueue> getInputQueue(const std::string &name, unsigned int maxSize, bool blocking = true)

Gets an input queue corresponding to stream name. If it doesn’t exist it throws. Also sets queue options

Return

Smart pointer to DataInputQueue

Parameters
  • name: Queue/stream name, set in XLinkOut node

  • maxSize: Maximum number of messages in queue

  • blocking: Queue behavior once full. True: blocking, false: overwriting of oldest messages. Default: true

std::vector<std::string> getInputQueueNames() const

Get all available input queue names

Return

Vector of input queue names

std::vector<std::string> getQueueEvents(const std::vector<std::string> &queueNames, std::size_t maxNumEvents = std::numeric_limits<std::size_t>::max(), std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until any of specified queues has received a message

Return

Names of queues which received messages first

Parameters
  • queueNames: Names of queues for which to block

  • maxNumEvents: Maximum number of events to remove from queue - Default is unlimited

  • timeout: Timeout after which return regardless. If negative then wait is indefinite - Default is -1

std::vector<std::string> getQueueEvents(std::string queueName, std::size_t maxNumEvents = std::numeric_limits<std::size_t>::max(), std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until specified queue has received a message

Return

Names of queues which received messages first

Parameters
  • queueName: Name of queues for which to wait for

  • maxNumEvents: Maximum number of events to remove from queue. Default is unlimited

  • timeout: Timeout after which return regardless. If negative then wait is indefinite. Default is -1

std::vector<std::string> getQueueEvents(std::size_t maxNumEvents = std::numeric_limits<std::size_t>::max(), std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until any any queue has received a message

Return

Names of queues which received messages first

Parameters
  • maxNumEvents: Maximum number of events to remove from queue. Default is unlimited

  • timeout: Timeout after which return regardless. If negative then wait is indefinite. Default is -1

std::string getQueueEvent(const std::vector<std::string> &queueNames, std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until any of specified queues has received a message

Return

Queue name which received a message first

Parameters
  • queueNames: Names of queues for which to wait for

  • timeout: Timeout after which return regardless. If negative then wait is indefinite. Default is -1

std::string getQueueEvent(std::string queueName, std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until specified queue has received a message

Return

Queue name which received a message

Parameters
  • queueNames: Name of queues for which to wait for

  • timeout: Timeout after which return regardless. If negative then wait is indefinite. Default is -1

std::string getQueueEvent(std::chrono::microseconds timeout = std::chrono::microseconds(-1))

Gets or waits until any queue has received a message

Return

Queue name which received a message

Parameters
  • timeout: Timeout after which return regardless. If negative then wait is indefinite. Default is -1

std::vector<CameraBoardSocket> getConnectedCameras()

Get cameras that are connected to the device

Return

Vector of connected cameras

MemoryInfo getDdrMemoryUsage()

Retrieves current DDR memory information from device

Return

Used, remaining and total ddr memory

MemoryInfo getCmxMemoryUsage()

Retrieves current CMX memory information from device

Return

Used, remaining and total cmx memory

MemoryInfo getLeonCssHeapUsage()

Retrieves current CSS Leon CPU heap information from device

Return

Used, remaining and total heap memory

MemoryInfo getLeonMssHeapUsage()

Retrieves current MSS Leon CPU heap information from device

Return

Used, remaining and total heap memory

ChipTemperature getChipTemperature()

Retrieves current chip temperature as measured by device

Return

Temperature of various onboard sensors

CpuUsage getLeonCssCpuUsage()

Retrieves average CSS Leon CPU usage

Return

Average CPU usage and sampling duration

CpuUsage getLeonMssCpuUsage()

Retrieves average MSS Leon CPU usage

Return

Average CPU usage and sampling duration

void close()

Explicitly closes connection to device.

Note

This function does not need to be explicitly called as destructor closes the device automatically

bool isClosed() const

Is the device already closed (or disconnected)

Public Static Functions

template<typename Rep, typename Period>
std::tuple<bool, DeviceInfo> getAnyAvailableDevice(std::chrono::duration<Rep, Period> timeout)

Waits for any available device with a timeout

Return

Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

Parameters
  • timeout: duration of time to wait for the any device

std::tuple<bool, DeviceInfo> getAnyAvailableDevice()

Gets any available device

Return

Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

std::tuple<bool, DeviceInfo> getFirstAvailableDevice()

Gets first available device. Device can be either in XLINK_UNBOOTED or XLINK_BOOTLOADER state

Return

Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

std::tuple<bool, DeviceInfo> getDeviceByMxId(std::string mxId)

Finds a device by MX ID. Example: 14442C10D13EABCE00

Return

Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

Parameters
  • mxId: MyraidX ID which uniquely specifies a device

std::vector<DeviceInfo> getAllAvailableDevices()

Returns all connected devices

Return

Vector of connected devices

std::vector<std::uint8_t> getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version = Pipeline::DEFAULT_OPENVINO_VERSION)

Gets device firmware binary for a specific OpenVINO version

Return

Firmware binary

Parameters
  • usb2Mode: USB2 mode firmware

  • version: Version of OpenVINO which firmware will support

Public Static Attributes

constexpr std::chrono::seconds DEFAULT_SEARCH_TIME = {3}

Default search time for constructors which discover devices.

constexpr std::size_t EVENT_QUEUE_MAXIMUM_SIZE = {2048}

Maximum number of elements in event queue.

constexpr float DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ = {1.0f}

Default rate at which system information is logged.

class DeviceBootloader
#include <DeviceBootloader.hpp>

Represents the DepthAI bootloader with the methods to interact with it.

Public Functions

DeviceBootloader(const DeviceInfo &devInfo)

Connects to or boots device in bootloader mode depending on devInfo state.

Parameters
  • devInfo: DeviceInfo of which to boot or connect to

DeviceBootloader(const DeviceInfo &devInfo, const std::string &pathToBootloader)

Connects to or boots device in bootloader mode depending on devInfo state with a custom bootloader firmware.

Parameters
  • devInfo: DeviceInfo of which to boot or connect to

  • pathToBootloader: Custom bootloader firmware to boot

DeviceBootloader(const DeviceInfo &devInfo, const char *pathToBootloader)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

std::tuple<bool, std::string> flash(std::function<void(float)> progressCallback, Pipeline &pipeline, )

Flashes a give pipeline to the board.

Parameters
  • progressCallback: Callback that sends back a value between 0..1 which signifies current flashing progress

  • pipeline: Pipeline to flash to the board

std::tuple<bool, std::string> flashDepthaiApplicationPackage(std::function<void(float)> progressCallback, std::vector<uint8_t> package, )

Flashes a specific depthai application package that was generated using createDepthaiApplicationPackage or saveDepthaiApplicationPackage

Parameters
  • progressCallback: Callback that sends back a value between 0..1 which signifies current flashing progress

  • package: Depthai application package to flash to the board

std::tuple<bool, std::string> flashBootloader(std::function<void(float)> progressCallback, std::string path = "", )

Flashes bootloader to the current board

Parameters
  • progressCallback: Callback that sends back a value between 0..1 which signifies current flashing progress

  • path: Optional parameter to custom bootloader to flash

Version getVersion()

Return

Version of current running bootloader

bool isEmbeddedVersion()

Return

True whether the bootloader running is flashed or booted by library

void close()

Explicitly closes connection to device.

Note

This function does not need to be explicitly called as destructor closes the device automatically

bool isClosed() const

Is the device already closed (or disconnected)

Public Static Functions

std::tuple<bool, DeviceInfo> getFirstAvailableDevice()

Searches for connected devices in either UNBOOTED or BOOTLOADER states and returns first available.

Return

Tuple of boolean and DeviceInfo. If found boolean is true and DeviceInfo describes the device. Otherwise false

std::vector<DeviceInfo> getAllAvailableDevices()

Searches for connected devices in either UNBOOTED or BOOTLOADER states.

Return

Vector of all found devices

std::vector<uint8_t> createDepthaiApplicationPackage(Pipeline &pipeline, std::string pathToCmd = "")

Creates application package which can be flashed to depthai device.

Return

Depthai application package

Parameters
  • pipeline: Pipeline from which to create the application package

  • pathToCmd: Optional path to custom device firmware

void saveDepthaiApplicationPackage(std::string path, Pipeline &pipeline, std::string pathToCmd = "")

Saves application package to a file which can be flashed to depthai device.

Parameters
  • path: Path where to save the application package

  • pipeline: Pipeline from which to create the application package

  • pathToCmd: Optional path to custom device firmware

Version getEmbeddedBootloaderVersion()

Return

Embedded bootloader version

std::vector<std::uint8_t> getEmbeddedBootloaderBinary()

Return

Embedded bootloader binary

struct Version
#include <DeviceBootloader.hpp>

Bootloader version structure.

Public Functions

Version(const std::string &v)

Construct Version from string.

Version(unsigned major, unsigned minor, unsigned patch)

Construct Version major, minor and patch numbers.

std::string toString() const

Convert Version to string.

struct DeviceInfo
#include <XLinkConnection.hpp>

Describes a connected device

struct GlobalProperties
#include <GlobalProperties.hpp>

Specify properties which apply for whole pipeline

Public Members

double leonCssFrequencyHz = 700 * 1000 * 1000

Set frequency of Leon OS - Increasing can improve performance, at the cost of higher power draw

double leonMssFrequencyHz = 700 * 1000 * 1000

Set frequency of Leon RT - Increasing can improve performance, at the cost of higher power draw

class ImageManipConfig : public dai::Buffer
#include <ImageManipConfig.hpp>

ImageManipConfig message. Specifies image manipulation options like:

  • Crop

  • Resize

  • Warp

Public Functions

ImageManipConfig()

Construct ImageManipConfig message.

void setCropRect(float xmin, float ymin, float xmax, float ymax)

Specifies crop with rectangle with normalized values (0..1)

Parameters
  • xmin: Top left X coordinate of rectangle

  • ymin: Top left Y coordinate of rectangle

  • xmax: Bottom right X coordinate of rectangle

  • ymax: Bottom right Y coordinate of rectangle

void setCropRotatedRect(RotatedRect rr, bool normalizedCoords = true)

Specifies crop with rotated rectangle. Optionally as non normalized coordinates

Parameters
  • rr: Rotated rectangle which specifies crop

  • normalizedCoords: If true coordinates are in normalized range (0..1) otherwise absolute

void setCenterCrop(float ratio, float whRatio = 1.0f)

Specifies a centered crop.

Parameters
  • ratio: Ratio between input image and crop region (0..1)

  • whRatio: Crop region aspect ratio - 1 equals to square, 1.7 equals to 16:9, …

void setWarpTransformFourPoints(std::vector<Point2f> pt, bool normalizedCoords)

Specifies warp by suppling 4 points in either absolute or normalized coordinates

Parameters
  • pt: 4 points specifying warp

  • normalizedCoords: If true pt is interpreted as normalized, absolute otherwise

void setWarpTransformMatrix3x3(std::vector<float> mat)

Specifies warp with a 3x3 matrix

Parameters
  • mat: 3x3 matrix

void setWarpBorderReplicatePixels()

Specifies that warp replicates border pixels

void setWarpBorderFillColor(int red, int green, int blue)

Specifies fill color for border pixels. Example:

  • setWarpBorderFillColor(255,255,255) -> white

  • setWarpBorderFillColor(0,0,255) -> blue

Parameters
  • red: Red component

  • green: Green component

  • blue: Blue component

void setRotationDegrees(float deg)

Specifies clockwise rotation in degrees

Parameters
  • deg: Rotation in degrees

void setRotationRadians(float rad)

Specifies clockwise rotation in radians

Parameters
  • rad: Rotation in radians

void setResize(int w, int h)

Specifies output image size. After crop stage the image will be streched to fit.

Parameters
  • w: Width in pixels

  • h: Height in pixels

void setResizeThumbnail(int w, int h, int bgRed = 0, int bgGreen = 0, int bgBlue = 0)

Specifies output image size. After crop stage the image will be resized by preserving aspect ration. Optionally background can be specified.

Parameters
  • w: Width in pixels

  • h: Height in pixels

  • bgRed: Red component

  • bgGreen: Green component

  • bgBlue: Blue component

void setFrameType(ImgFrame::Type name)

Specify output frame type.

Parameters
  • name: Frame type

void setHorizontalFlip(bool flip)

Specify horizontal flip

Parameters
  • flip: True to enable flip, false otherwise

void setReusePreviousImage(bool reuse)

Instruct ImageManip to not remove current image from its queue and use the same for next message.

Parameters
  • reuse: True to enable reuse, false otherwise

void setSkipCurrentImage(bool skip)

Instructs ImageManip to skip current image and wait for next in queue.

Parameters
  • skip: True to skip current image, false otherwise

void setKeepAspectRatio(bool keep)

Specifies to whether to keep aspect ratio or not

float getCropXMin() const

Return

Top left X coordinate of crop region

float getCropYMin() const

Return

Top left Y coordinate of crop region

float getCropXMax() const

Return

Bottom right X coordinate of crop region

float getCropYMax() const

Return

Bottom right Y coordinate of crop region

int getResizeWidth() const

Return

Output image width

int getResizeHeight() const

Return

Output image height

bool isResizeThumbnail() const

Return

True if resize thumbnail mode is set, false otherwise

struct ImageManipProperties
#include <ImageManipProperties.hpp>

Specify ImageManip options

Public Members

RawImageManipConfig initialConfig

Initial configuration for ImageManip node.

bool inputConfigSync = false

Whether to wait for config at ‘inputConfig’ IO.

int outputFrameSize = 1 * 1024 * 1024

Maximum output frame size in bytes (eg: 300x300 BGR image -> 300*300*3 bytes)

int numFramesPool = 4

Num frames in output pool.

struct ImgDetection

Subclassed by dai::SpatialImgDetection

class ImgDetections : public dai::Buffer
#include <ImgDetections.hpp>

ImgDetections message. Carries normalized detection results

Public Functions

ImgDetections()

Construct ImgDetections message.

Public Members

std::vector<ImgDetection> &detections

Detections.

class ImgFrame : public dai::Buffer
#include <ImgFrame.hpp>

ImgFrame message. Carries image data and metadata.

Public Functions

ImgFrame()

Construct ImgFrame message. Timestamp is set to now

std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> getTimestamp() const

Retrievies image timestamp related to steady_clock / time.monotonic

unsigned int getInstanceNum() const

Retrievies instance number

unsigned int getCategory() const

Retrievies image category

unsigned int getSequenceNum() const

Retrievies image sequence number

unsigned int getWidth() const

Retrievies image width in pixels

unsigned int getHeight() const

Retrievies image height in pixels

Type getType() const

Retrieves image type

void setTimestamp(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp)

Specifies current timestamp, related to steady_clock / time.monotonic

void setInstanceNum(unsigned int instance)

Instance number relates to the origin of the frame (which camera)

Parameters
  • instance: Instance number

void setCategory(unsigned int category)

Parameters
  • category: Image category

void setSequenceNum(unsigned int seq)

Specifies sequence number

Parameters
  • seq: Sequence number

void setWidth(unsigned int width)

Specifies frame width

Parameters
  • width: frame width

void setHeight(unsigned int)

Specifies frame height

Parameters
  • width: frame height

void setType(Type type)

Specifies frame type, RGB, BGR, …

Parameters
  • type: Type of image

void setFrame(cv::Mat frame)

Copies cv::Mat data to

ImgFrame buffer
Note

This API only available if OpenCV support is enabled

Parameters
  • frame: Input cv::Mat frame from which to copy the data

cv::Mat getFrame(bool copy = false)

Retrieves data as cv::Mat with specified width, height and type

Note

This API only available if OpenCV support is enabled

Return

cv::Mat with corresponding to ImgFrame parameters

Parameters
  • copy: If false only a reference to data is made, otherwise a copy

cv::Mat getCvFrame()

Retrieves cv::Mat suitable for use in common opencv functions.

ImgFrame is converted to color BGR interleaved or grayscale depending on type.
Note

This API only available if OpenCV support is enabled

A copy is always made

Return

cv::Mat for use in opencv functions

template<typename T>
class LockingQueue
struct LogMessage
struct MemoryInfo
#include <MemoryInfo.hpp>

MemoryInfo structure

Free, remaining and total memory stats

struct MonoCameraProperties
#include <MonoCameraProperties.hpp>

Specify MonoCamera options such as camera ID, …

Public Types

enum SensorResolution

Select the camera sensor resolution: 1280×720, 1280×800, 640×400

Values:

enumerator THE_720_P
enumerator THE_800_P
enumerator THE_400_P

Public Members

CameraBoardSocket boardSocket = CameraBoardSocket::AUTO

Which socket will mono camera use

CameraImageOrientation imageOrientation = CameraImageOrientation::AUTO

Camera sensor image orientation / pixel readout

SensorResolution resolution = SensorResolution::THE_720_P

Select the camera sensor resolution

float fps = 30.0

Camera sensor FPS

struct MyConsumerProperties
#include <MyConsumerProperties.hpp>

Specify message and processor placement of MyConsumer node

Public Members

ProcessorType processorPlacement

On which processor the node will be placed

struct MyProducerProperties
#include <MyProducerProperties.hpp>

Specify message and processor placement of MyProducer node

Public Members

tl::optional<std::string> message

Message to be sent forward

ProcessorType processorPlacement = ProcessorType::LOS

On which processor the node will be placed

struct NeuralNetworkProperties
#include <NeuralNetworkProperties.hpp>

Specify NeuralNetwork options such as blob path, …

Subclassed by dai::DetectionNetworkProperties

Public Members

tl::optional<std::uint32_t> blobSize

Blob binary size in bytes

std::string blobUri

Uri which points to blob

std::uint32_t numFrames = 8

Number of available output tensors in pool

std::uint32_t numThreads = 0

Number of threads to create for running inference. 0 = auto

std::uint32_t numNCEPerThread = 0

Number of NCE (Neural Compute Engine) per inference thread. 0 = auto

class NNData : public dai::Buffer
#include <NNData.hpp>

NNData message. Carries tensors and their metadata

Public Functions

NNData()

Construct NNData message.

void setLayer(const std::string &name, std::vector<std::uint8_t> data)

Set a layer with datatype U8.

Parameters
  • name: Name of the layer

  • data: Data to store

void setLayer(const std::string &name, const std::vector<int> &data)

Set a layer with datatype U8. Integers are casted to bytes.

Parameters
  • name: Name of the layer

  • data: Data to store

void setLayer(const std::string &name, std::vector<float> data)

Set a layer with datatype FP16. Float values are converted to FP16.

Parameters
  • name: Name of the layer

  • data: Data to store

void setLayer(const std::string &name, std::vector<double> data)

Set a layer with datatype FP16. Double values are converted to FP16.

Parameters
  • name: Name of the layer

  • data: Data to store

std::vector<std::string> getAllLayerNames() const

Return

Names of all layers added

std::vector<TensorInfo> getAllLayers() const

Return

All layers and their information

bool getLayer(const std::string &name, TensorInfo &tensor) const

Retrieve layers tensor information

Return

True if layer exists, false otherwise

Parameters
  • name: Name of the layer

  • [out] tensor: Outputs tensor infromation of that layer

bool hasLayer(const std::string &name) const

Checks if given layer exists

Return

True if layer exists, false otherwise

Parameters
  • name: Name of the layer

bool getLayerDatatype(const std::string &name, TensorInfo::DataType &datatype) const

Retrieve datatype of a layers tensor

Return

True if layer exists, false otherwise

Parameters
  • name: Name of the layer

  • [out] datatype: Datatype of layers tensor

std::vector<std::uint8_t> getLayerUInt8(const std::string &name) const

Convinience function to retrieve U8 data from layer

Return

U8 binary data

Parameters
  • name: Name of the layer

std::vector<float> getLayerFp16(const std::string &name) const

Convinience function to retrieve float values from layers FP16 tensor

Return

Float data

Parameters
  • name: Name of the layer

std::vector<std::int32_t> getLayerInt32(const std::string &name) const

Convinience function to retrieve INT32 values from layers tensor

Return

INT32 data

Parameters
  • name: Name of the layer

std::vector<std::uint8_t> getFirstLayerUInt8() const

Convinience function to retrieve U8 data from first layer

Return

U8 binary data

std::vector<float> getFirstLayerFp16() const

Convinience function to retrieve float values from first layers FP16 tensor

Return

Float data

std::vector<std::int32_t> getFirstLayerInt32() const

Convinience function to retrieve INT32 values from first layers tensor

Return

INT32 data

class Node
#include <Node.hpp>

Abstract Node.

Subclassed by dai::node::ColorCamera, dai::node::ImageManip, dai::node::MonoCamera, dai::node::MyProducer, dai::node::NeuralNetwork, dai::node::ObjectTracker, dai::node::SpatialLocationCalculator, dai::node::SPIOut, dai::node::StereoDepth, dai::node::SystemLogger, dai::node::VideoEncoder, dai::node::XLinkIn, dai::node::XLinkOut

Public Types

using Id = std::int64_t

Node identificator. Unique for every node on a single Pipeline.

Public Functions

std::string getName() const = 0

Retrieves nodes name.

std::vector<Output> getOutputs() = 0

Retrieves all nodes outputs.

std::vector<Input> getInputs() = 0

Retrieves all nodes inputs.

std::vector<std::shared_ptr<Asset>> getAssets()

Retrieves all nodes assets.

Public Members

const Id id

Id of node.

struct Connection
#include <Node.hpp>

Connection between an Input and Output.

struct NodeConnectionSchema
#include <NodeConnectionSchema.hpp>

Specifies a connection between nodes IOs

struct NodeIoInfo
struct NodeObjInfo
struct ObjectTrackerProperties
#include <ObjectTrackerProperties.hpp>

Properties for ObjectTracker

class OpenVINO
#include <OpenVINO.hpp>

Support for basic OpenVINO related actions like version identification of neural network blobs,…

Public Types

enum Version

OpenVINO Version supported version information.

Values:

enumerator VERSION_2020_1
enumerator VERSION_2020_2
enumerator VERSION_2020_3
enumerator VERSION_2020_4
enumerator VERSION_2021_1
enumerator VERSION_2021_2
enumerator VERSION_2021_3

Public Static Functions

std::vector<Version> getVersions()

Return

Supported versions

std::string getVersionName(Version version)

Returns string representation of a given version

Return

Name of a given version

Parameters

Version parseVersionName(const std::string &versionString)

Creates Version from string representation. Throws if not possible.

Return

Version object if successful

Parameters
  • versionString: Version as string

std::vector<Version> getBlobSupportedVersions(std::uint32_t majorVersion, std::uint32_t minorVersion)

Returns a list of potentionally supported versions for a specified blob major and minor versions.

Return

Vector of potentionally supported versions

Parameters
  • majorVersion: Major version from OpenVINO blob

  • minorVersion: Minor version from OpenVINO blob

Version getBlobLatestSupportedVersion(std::uint32_t majorVersion, std::uint32_t minorVersion)

Returns latest potentionally supported version by a given blob version.

Return

Latest potentionally supported version

Parameters
  • majorVersion: Major version from OpenVINO blob

  • minorVersion: Minor version from OpenVINO blob

bool areVersionsBlobCompatible(Version v1, Version v2)

Checks whether two blob versions are compatible

template<typename T>
class Pimpl
class Pipeline
#include <Pipeline.hpp>

Represents the pipeline, set of nodes and connections between them.

Public Functions

Pipeline()

Constructs a new pipeline

Pipeline clone() const

Clone the pipeline (Creates a copy)

GlobalProperties getGlobalProperties() const

Return

Global properties of current pipeline

PipelineSchema getPipelineSchema()

Return

Pipeline schema

template<class N>
std::shared_ptr<N> create()

Adds a node to pipeline.

Node is specified by template argument N

void remove(std::shared_ptr<Node> node)

Removes a node from pipeline.

std::vector<std::shared_ptr<const Node>> getAllNodes() const

Get a vector of all nodes.

std::vector<std::shared_ptr<Node>> getAllNodes()

Get a vector of all nodes.

std::shared_ptr<const Node> getNode(Node::Id id) const

Get node with id if it exists, nullptr otherwise.

std::shared_ptr<Node> getNode(Node::Id id)

Get node with id if it exists, nullptr otherwise.

std::vector<Node::Connection> getConnections() const

Get all connections.

const NodeConnectionMap &getConnectionMap() const

Get a reference to internal connection representation.

const NodeMap &getNodeMap() const

Get a reference to internal node map.

void link(const Node::Output &out, const Node::Input &in)

Link output to an input. Both nodes must be on the same pipeline

Throws an error if they aren’t or cannot be connected

Parameters
  • out: Nodes output to connect from

  • in: Nodes input to connect to

void unlink(const Node::Output &out, const Node::Input &in)

Unlink output from an input.

Throws an error if link doesn’t exists

Parameters
  • out: Nodes output to unlink from

  • in: Nodes input to unlink to

AssetManager getAllAssets() const

Get assets on the pipeline includes nodes assets.

const AssetManager &getAssetManager() const

Get pipelines AssetManager as reference.

AssetManager &getAssetManager()

Get pipelines AssetManager as reference.

void setOpenVINOVersion(OpenVINO::Version version)

Set a specific OpenVINO version to use with this pipeline.

OpenVINO::Version getOpenVINOVersion() const

Get required OpenVINO version to run this pipeline.

Public Static Attributes

constexpr auto DEFAULT_OPENVINO_VERSION = PipelineImpl::DEFAULT_OPENVINO_VERSION

Default Pipeline openvino version.

class PipelineImpl
struct PipelineSchema
#include <PipelineSchema.hpp>

Specifies whole pipeline, nodes, properties and connections between nodes IOs

struct Point2f
#include <Point2f.hpp>

Point2f structure

x and y coordinates that define a 2D point.

struct Point3f
#include <Point3f.hpp>

Point3f structure

x,y,z coordinates that define a 3D point.

struct RawBuffer

Subclassed by dai::RawCameraControl, dai::RawImageManipConfig, dai::RawImgDetections, dai::RawImgFrame, dai::RawNNData, dai::RawSpatialImgDetections, dai::RawSpatialLocationCalculatorConfig, dai::RawSpatialLocations, dai::RawSystemInformation, dai::RawTracklets

struct RawCameraControl : public dai::RawBuffer

Public Members

uint8_t lensPosition = 0

Lens/VCM position, range: 0..255. Used with autoFocusMode = OFF. With current IMX378 modules:

  • max 255: macro focus, at 8cm distance

  • infinite focus at about 120..130 (may vary from module to module)

  • lower values lead to out-of-focus (lens too close to the sensor array)

struct ManualExposureParams
struct RegionParams
struct RawImageManipConfig : public dai::RawBuffer
struct CropConfig
struct CropRect
struct FormatConfig
struct ResizeConfig

Public Members

bool keepAspectRatio = true

Whether to keep aspect ratio of input or not

struct RawImgDetections : public dai::RawBuffer
struct RawImgFrame : public dai::RawBuffer
struct Specs
struct RawNNData : public dai::RawBuffer
struct RawSpatialImgDetections : public dai::RawBuffer
struct RawSpatialLocationCalculatorConfig : public dai::RawBuffer
struct RawSpatialLocations : public dai::RawBuffer
struct RawSystemInformation : public dai::RawBuffer
#include <RawSystemInformation.hpp>

System information of device

Memory usage, cpu usage and chip temperature

Public Members

MemoryInfo ddrMemoryUsage

DDR memory usage.

MemoryInfo cmxMemoryUsage

CMX memory usage.

MemoryInfo leonCssMemoryUsage

LeonCss heap usage.

MemoryInfo leonMssMemoryUsage

LeonMss heap usage.

CpuUsage leonCssCpuUsage

LeonCss cpu usage.

CpuUsage leonMssCpuUsage

LeonMss cpu usage.

ChipTemperature chipTemperature

Chip temperatures.

struct RawTracklets : public dai::RawBuffer
struct Rect
#include <Rect.hpp>

Rect structure

x,y coordinates together with width and height that define a rectangle. Can be either normalized [0,1] or absolute representation.

Public Functions

Point2f topLeft() const

The top-left corner.

Point2f bottomRight() const

The bottom-right corner

Size2f size() const

Size (width, height) of the rectangle

float area() const

Area (width*height) of the rectangle

bool empty() const

True if rectangle is empty.

bool contains(const Point2f &pt) const

Checks whether the rectangle contains the point.

bool isNormalized() const

Whether rectangle is normalized (coordinates in [0,1] range) or not.

Rect denormalize(int width, int height)

Denormalize rectangle.

Parameters
  • width: Destination frame width.

  • height: Destination frame height.

Rect normalize(int width, int height)

Normalize rectangle.

Parameters
  • width: Source frame width.

  • height: Source frame height.

struct RotatedRect

Public Members

float angle

degrees, increasing clockwise

struct Size2f
struct SpatialDetectionNetworkProperties : public dai::DetectionNetworkProperties
#include <SpatialDetectionNetworkProperties.hpp>

Properties for SpatialDetectionNetwork

struct SpatialImgDetection : public dai::ImgDetection
#include <RawSpatialImgDetections.hpp>

Spatial image detection structure

Contains image detection results together with spatial location data.

class SpatialImgDetections : public dai::Buffer
#include <SpatialImgDetections.hpp>

SpatialImgDetections message. Carries detection results together with spatial location data

Public Functions

SpatialImgDetections()

Construct SpatialImgDetections message.

Public Members

std::vector<SpatialImgDetection> &detections

Detection results.

class SpatialLocationCalculatorConfig : public dai::Buffer
#include <SpatialLocationCalculatorConfig.hpp>

SpatialLocationCalculatorConfig message. Carries ROI (region of interest) and threshold for depth calculation

Public Functions

SpatialLocationCalculatorConfig()

Construct SpatialLocationCalculatorConfig message.

void setROIs(std::vector<SpatialLocationCalculatorConfigData> ROIs)

Set a vector of ROIs as configuration data.

Parameters
  • ROIs: Vector of configuration parameters for ROIs (region of interests)

void addROI(SpatialLocationCalculatorConfigData &ROI)

Add a new ROI to configuration data.

Parameters
  • roi: Configuration parameters for ROI (region of interest)

std::vector<SpatialLocationCalculatorConfigData> getConfigData() const

Retrieve configuration data for SpatialLocationCalculator

Return

Vector of configuration parameters for ROIs (region of interests)

struct SpatialLocationCalculatorConfigData
struct SpatialLocationCalculatorConfigThresholds
#include <RawSpatialLocationCalculatorConfig.hpp>

Spatial location configuration thresholds structure

Contains configuration data for lower and upper threshold in millimeters for ROI. Values outside of threshold range will be ignored when calculating spatial coordinates from depth map.

class SpatialLocationCalculatorData : public dai::Buffer
#include <SpatialLocationCalculatorData.hpp>

SpatialLocationCalculatorData message. Carries spatial information (X,Y,Z) and their configuration parameters

Public Functions

SpatialLocationCalculatorData()

Construct SpatialLocationCalculatorData message.

std::vector<SpatialLocations> &getSpatialLocations() const

Retrieve configuration data for SpatialLocationCalculatorData.

Return

Vector of spatial location data, carrying spatial information (X,Y,Z)

struct SpatialLocationCalculatorProperties
#include <SpatialLocationCalculatorProperties.hpp>

Specify SpatialLocationCalculator options

Public Members

bool inputConfigSync = false

Whether to wait for config at ‘inputConfig’ IO.

struct SpatialLocations
#include <RawSpatialLocations.hpp>

Spatial location information structure

Contains configuration data, average depth for the calculated ROI on depth map. Together with spatial coordinates: x,y,z relative to the center of depth map. Units are in millimeters.

struct SPIOutProperties
#include <SPIOutProperties.hpp>

Properties for SPIOut node

Public Members

std::string streamName

Output stream name.

int busId

SPI bus to use.

struct StereoDepthProperties
#include <StereoDepthProperties.hpp>

Specify StereoDepth options

Public Types

enum MedianFilter

Median filter config for disparity post-processing

Values:

enumerator MEDIAN_OFF
enumerator KERNEL_3x3
enumerator KERNEL_5x5
enumerator KERNEL_7x7
enum DepthAlign

Align the disparity/depth to the perspective of a rectified output, or center it

Values:

enumerator RECTIFIED_RIGHT
enumerator RECTIFIED_LEFT
enumerator CENTER

Public Members

std::vector<std::uint8_t> calibration

Calibration data byte array

MedianFilter median = MedianFilter::KERNEL_5x5

Set kernel size for disparity/depth median filtering, or disable

DepthAlign depthAlign = DepthAlign::RECTIFIED_RIGHT

Set the disparity/depth alignment to the perspective of a rectified output, or center it

CameraBoardSocket depthAlignCamera = CameraBoardSocket::AUTO

Which camera to align disparity/depth to. When configured (not AUTO), takes precedence over ‘depthAlign’

std::int32_t confidenceThreshold = 200

Confidence threshold for disparity calculation, 0..255

bool enableLeftRightCheck = false

Computes and combines disparities in both L-R and R-L directions, and combine them. For better occlusion handling

bool enableSubpixel = false

Computes disparity with sub-pixel interpolation (5 fractional bits), suitable for long range

bool enableExtendedDisparity = false

Disparity range increased from 96 to 192, combined from full resolution and downscaled images. Suitable for short range objects

bool rectifyMirrorFrame = true

Mirror rectified frames: true to have disparity/depth normal (non-mirrored)

std::int32_t rectifyEdgeFillColor = -1

Fill color for missing data at frame edges: grayscale 0..255, or -1 to replicate pixels

tl::optional<std::int32_t> width

Input frame width. Optional (taken from MonoCamera nodes if they exist)

tl::optional<std::int32_t> height

Input frame height. Optional (taken from MonoCamera nodes if they exist)

class SystemInformation : public dai::Buffer
#include <SystemInformation.hpp>

SystemInformation message. Carries memory usage, cpu usage and chip temperatures.

Public Functions

SystemInformation()

Construct SystemInformation message.

struct SystemLoggerProperties
#include <SystemLoggerProperties.hpp>

SystemLoggerProperties

Public Members

float rateHz = 1.0f

Rate at which the messages are going to be sent in hertz

struct TensorInfo
struct Timestamp
struct Tracklet
#include <RawTracklets.hpp>

Tracklet structure

Contains tracklets from object tracker output.

Public Members

Rect roi

Tracked region of interest.

std::int32_t id

Tracklet’s ID.

std::int32_t label

Tracklet’s label ID.

std::int32_t age

Number of frames it is being tracked for.

TrackingStatus status

Status of tracklet.

ImgDetection srcImgDetection

Image detection that is tracked.

Point3f spatialCoordinates

Spatial coordinates of tracklet.

class Tracklets : public dai::Buffer
#include <Tracklets.hpp>

Tracklets message. Carries object tracking information.

Public Functions

Tracklets()

Construct Tracklets message.

Public Members

std::vector<Tracklet> &tracklets

Retrieve data for Tracklets.

Return

Vector of object tracker data, carrying tracking information.

struct VideoEncoderProperties
#include <VideoEncoderProperties.hpp>

Specify VideoEncoder options such as profile, bitrate, …

Public Types

enum RateControlMode

Rate control mode specifies if constant or variable bitrate should be used (H264 / H265)

Values:

enumerator CBR
enumerator VBR
enum Profile

Encoding profile, H264, H265 or MJPEG

Values:

enumerator H264_BASELINE
enumerator H264_HIGH
enumerator H264_MAIN
enumerator H265_MAIN
enumerator MJPEG

Public Members

std::int32_t bitrate = 8000

Specifies prefered bitrate (kb) of compressed output bitstream

std::int32_t keyframeFrequency = 30

Every x number of frames a keyframe will be inserted

std::int32_t maxBitrate = 8000

Specifies maximum bitrate (kb) of compressed output bitstream

std::int32_t numBFrames = 0

Specifies number of B frames to be inserted

std::uint32_t numFramesPool = 4

This options specifies how many frames are available in this nodes pool (can help if receiver node is slow at consuming

Profile profile = Profile::H264_BASELINE

Encoding profile, H264, H265 or MJPEG

std::int32_t quality = 80

Value between 0-100% (approximates quality)

bool lossless = false

Lossless mode ([M]JPEG only)

RateControlMode rateCtrlMode = RateControlMode::CBR

Rate control mode specifies if constant or variable bitrate should be used (H264 / H265)

std::int32_t width = 1920

Input and compressed output frame width

std::int32_t height = 1080

Input and compressed output frame height

float frameRate = 30.0f

Frame rate

class XLinkConnection
#include <XLinkConnection.hpp>

Represents connection between host and device over XLink protocol

Public Functions

void close()

Explicitly closes xlink connection.

Note

This function does not need to be explicitly called as destructor closes the connection automatically

bool isClosed() const

Is the connection already closed (or disconnected)

struct XLinkInProperties
#include <XLinkInProperties.hpp>

Properties for XLinkIn which define stream name

Public Members

std::string streamName

Name of stream

std::uint32_t maxDataSize = dai::XLINK_USB_BUFFER_MAX_SIZE

Maximum input data size

std::uint32_t numFrames = 8

Number of frames in pool

struct XLinkOutProperties
#include <XLinkOutProperties.hpp>

Properties for XLinkOut which define stream name

Public Members

float maxFpsLimit = -1

Set a limit to how many packets will be sent further to host

std::string streamName

Name of stream

bool metadataOnly = false

Whether to transfer data or only object attributes

class XLinkStream
namespace bootloader

Variables

namespace request

Enums

enum Command

Values:

enumerator USB_ROM_BOOT
enumerator BOOT_APPLICATION
enumerator UPDATE_FLASH
enumerator GET_BOOTLOADER_VERSION
struct BootApplication
struct GetBootloaderVersion
struct UpdateFlash
struct UsbRomBoot
namespace response

Enums

enum Command

Values:

enumerator FLASH_COMPLETE
enumerator FLASH_STATUS_UPDATE
enumerator BOOTLOADER_VERSION
struct BootloaderVersion
struct FlashComplete
struct FlashStatusUpdate
namespace node
class ColorCamera : public dai::Node
#include <ColorCamera.hpp>

ColorCamera node. For use with color sensors.

Public Functions

ColorCamera(const std::shared_ptr<PipelineImpl> &par, int64_t nodeId)

Constructs ColorCamera node.

void setBoardSocket(CameraBoardSocket boardSocket)

Specify which board socket to use

Parameters
  • boardSocket: Board socket to use

CameraBoardSocket getBoardSocket() const

Retrieves which board socket to use

Return

Board socket to use

void setCamId(int64_t id)

Set which color camera to use.

int64_t getCamId() const

Get which color camera to use.

void setImageOrientation(CameraImageOrientation imageOrientation)

Set camera image orientation.

CameraImageOrientation getImageOrientation() const

Get camera image orientation.

void setColorOrder(ColorCameraProperties::ColorOrder colorOrder)

Set color order of preview output images. RGB or BGR.

ColorCameraProperties::ColorOrder getColorOrder() const

Get color order of preview output frames. RGB or BGR.

void setInterleaved(bool interleaved)

Set planar or interleaved data of preview output frames.

bool getInterleaved() const

Get planar or interleaved data of preview output frames.

void setFp16(bool fp16)

Set fp16 (0..255) data type of preview output frames.

bool getFp16() const

Get fp16 (0..255) data of preview output frames.

void setPreviewSize(int width, int height)

Set preview output size.

void setPreviewSize(std::tuple<int, int> size)

Set preview output size, as a tuple <width, height>

void setVideoSize(int width, int height)

Set video output size.

void setVideoSize(std::tuple<int, int> size)

Set video output size, as a tuple <width, height>

void setStillSize(int width, int height)

Set still output size.

void setStillSize(std::tuple<int, int> size)

Set still output size, as a tuple <width, height>

void setResolution(Properties::SensorResolution resolution)

Set sensor resolution.

Properties::SensorResolution getResolution() const

Get sensor resolution.

void setIspScale(int numerator, int denominator)

Set ‘isp’ output scaling (numerator/denominator), preserving the aspect ratio. The fraction numerator/denominator is simplified first to a irreducible form, then a set of hardware scaler constraints applies: max numerator = 16, max denominator = 63

void setIspScale(std::tuple<int, int> scale)

Set ‘isp’ output scaling, as a tuple <numerator, denominator>

void setIspScale(int horizNum, int horizDenom, int vertNum, int vertDenom)

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(std::tuple<int, int> horizScale, std::tuple<int, int> vertScale)

Set ‘isp’ output scaling, per each direction, as <numerator, denominator> tuples.

void setFps(float fps)

Set rate at which camera should produce frames

Parameters
  • fps: Rate in frames per second

float getFps() const

Get rate at which camera should produce frames

Return

Rate in frames per second

std::tuple<int, int> getPreviewSize() const

Get preview size as tuple.

int getPreviewWidth() const

Get preview width.

int getPreviewHeight() const

Get preview height.

std::tuple<int, int> getVideoSize() const

Get video size as tuple.

int getVideoWidth() const

Get video width.

int getVideoHeight() const

Get video height.

std::tuple<int, int> getStillSize() const

Get still size as tuple.

int getStillWidth() const

Get still width.

int getStillHeight() const

Get still height.

std::tuple<int, int> getResolutionSize() const

Get sensor resolution as size.

int getResolutionWidth() const

Get sensor resolution width.

int getResolutionHeight() const

Get sensor resolution height.

std::tuple<int, int> getIspSize() const

Get ‘isp’ output resolution as size, after scaling.

int getIspWidth() const

Get ‘isp’ output width.

int getIspHeight() const

Get ‘isp’ output height.

void sensorCenterCrop()

Specify sensor center crop. Resolution size / video size

void setSensorCrop(float x, float y)

Specifies sensor crop rectangle

Parameters
  • x: Top left X coordinate

  • y: Top left Y coordinate

std::tuple<float, float> getSensorCrop() const

Return

Sensor top left crop coordinates

float getSensorCropX() const

Get sensor top left x crop coordinate.

float getSensorCropY() const

Get sensor top left y crop coordinate.

void setWaitForConfigInput(bool wait)

Specify to wait until inputConfig receives a configuration message, before sending out a frame.

Parameters
  • wait: True to wait for inputConfig message, false otherwise

bool getWaitForConfigInput()

See

setWaitForConfigInput

Return

True if wait for inputConfig message, false otherwise

void setPreviewKeepAspectRatio(bool keep)

Specifies whether preview output should preserve aspect ratio, after downscaling from video size or not.

Parameters
  • keep: If true, a larger crop region will be considered to still be able to create the final image in the specified aspect ratio. Otherwise video size is resized to fit preview size

bool getPreviewKeepAspectRatio()

See

setPreviewKeepAspectRatio

Return

Preview keep aspect ratio option

Public Members

CameraControl initialControl

Initial control options to apply to sensor

Input inputConfig = {*this, "inputConfig", Input::Type::SReceiver, false, 8, {{DatatypeEnum::ImageManipConfig, false}}}

Input for ImageManipConfig message, which can modify crop paremeters in runtime

Default queue is non-blocking with size 8

Input inputControl = {*this, "inputControl", Input::Type::SReceiver, true, 8, {{DatatypeEnum::CameraControl, false}}}

Input for CameraControl message, which can modify camera parameters in runtime

Default queue is blocking with size 8

Output video = {*this, "video", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries NV12 encoded (YUV420, UV plane interleaved) frame data.

Suitable for use with VideoEncoder node

Output preview = {*this, "preview", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries BGR/RGB planar/interleaved encoded frame data.

Suitable for use with NeuralNetwork node

Output still = {*this, "still", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries NV12 encoded (YUV420, UV plane interleaved) frame data.

The message is sent only when a CameraControl message arrives to inputControl with captureStill command set.

Output isp = {*this, "isp", 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 raw = {*this, "raw", 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.

class DetectionNetwork : public dai::node::NeuralNetwork
#include <DetectionNetwork.hpp>

DetectionNetwork. Base for different network specializations.

Subclassed by dai::node::MobileNetDetectionNetwork, dai::node::SpatialDetectionNetwork, dai::node::YoloDetectionNetwork

Public Functions

std::string getName() const override

Retrieves nodes name.

std::vector<Output> getOutputs() override

Retrieves all nodes outputs.

std::vector<Input> getInputs() override

Retrieves all nodes inputs.

void setConfidenceThreshold(float thresh)

Specifies confidence threshold at which to filter the rest of the detections.

Parameters
  • thresh: Detection confidence must be greater than specified threshold to be added to the list

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 5, {{DatatypeEnum::Buffer, true}}}

Input message with data to be infered upon Default queue is blocking with size 5

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::ImgDetections, false}}}

Outputs ImgDetections message that carries parsed detection results.

Output passthrough = {*this, "passthrough", Output::Type::MSender, {{DatatypeEnum::Buffer, true}}}

Passthrough message on which the inference was performed.

Suitable for when input queue is set to non-blocking behavior.

class ImageManip : public dai::Node
#include <ImageManip.hpp>

ImageManip node. Capability to crop, resize, warp, … incoming image frames.

Public Functions

void setWaitForConfigInput(bool wait)

Specify whether or not wait until configuration message arrives to inputConfig Input.

Parameters
  • wait: True to wait for configuration message, false otherwise

void setNumFramesPool(int numFramesPool)

Specify number of frames in pool.

Parameters
  • numFramesPool: How many frames should the pool have

void setMaxOutputFrameSize(int maxFrameSize)

Specify maximum size of output image.

Parameters
  • maxFrameSize: Maximum frame size in bytes

Public Members

ImageManipConfig initialConfig

Initial config to use when manipulating frames

Input inputConfig = {*this, "inputConfig", Input::Type::SReceiver, true, 8, {{DatatypeEnum::ImageManipConfig, true}}}

Input ImageManipConfig message with ability to modify parameters in runtime Default queue is blocking with size 8

Input inputImage = {*this, "inputImage", Input::Type::SReceiver, true, 8, {{DatatypeEnum::ImgFrame, true}}}

Input image to be modified Default queue is blocking with size 8

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::ImgFrame, true}}}

Outputs ImgFrame message that carries modified image.

class MobileNetDetectionNetwork : public dai::node::DetectionNetwork
#include <DetectionNetwork.hpp>

MobileNetDetectionNetwork node. Parses MobileNet results.

class MobileNetSpatialDetectionNetwork : public dai::node::SpatialDetectionNetwork
#include <SpatialDetectionNetwork.hpp>

MobileNetSpatialDetectionNetwork. Mobilenet-SSD based network with spatial location data.

class MonoCamera : public dai::Node
#include <MonoCamera.hpp>

MonoCamera node. For use with grayscale sensors.

Public Functions

void setBoardSocket(CameraBoardSocket boardSocket)

Specify which board socket to use

Parameters
  • boardSocket: Board socket to use

CameraBoardSocket getBoardSocket() const

Retrieves which board socket to use

Return

Board socket to use

void setImageOrientation(CameraImageOrientation imageOrientation)

Set camera image orientation.

CameraImageOrientation getImageOrientation() const

Get camera image orientation.

void setResolution(Properties::SensorResolution resolution)

Set sensor resolution.

Properties::SensorResolution getResolution() const

Get sensor resolution.

void setFps(float fps)

Set rate at which camera should produce frames

Parameters
  • fps: Rate in frames per second

float getFps() const

Get rate at which camera should produce frames

Return

Rate in frames per second

std::tuple<int, int> getResolutionSize() const

Get sensor resolution as size.

int getResolutionWidth() const

Get sensor resolution width.

int getResolutionHeight() const

Get sensor resolution height.

Public Members

CameraControl initialControl

Initial control options to apply to sensor

Input inputControl = {*this, "inputControl", Input::Type::SReceiver, true, 8, {{DatatypeEnum::CameraControl, false}}}

Input for CameraControl message, which can modify camera parameters in runtime Default queue is blocking with size 8

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 encoded (grayscale) frame data.

Suitable for use StereoDepth node

class MyProducer : public dai::Node
class NeuralNetwork : public dai::Node
#include <NeuralNetwork.hpp>

NeuralNetwork node. Runs a neural inference on input data.

Subclassed by dai::node::DetectionNetwork

Public Functions

std::string getName() const override

Retrieves nodes name.

std::vector<Output> getOutputs() override

Retrieves all nodes outputs.

std::vector<Input> getInputs() override

Retrieves all nodes inputs.

void setBlobPath(const std::string &path)

Load network blob into assets and use once pipeline is started.

Throws if file doesn’t exist or isn’t a valid network blob.

Parameters
  • path: Path to network blob

void setNumPoolFrames(int numFrames)

Specifies how many frames will be avilable in the pool

Parameters
  • numFrames: How many frames will pool have

void setNumInferenceThreads(int numThreads)

How many threads should the node use to run the network.

Parameters
  • numThreads: Number of threads to dedicate to this node

void setNumNCEPerInferenceThread(int numNCEPerThread)

How many Neural Compute Engines should a single thread use for inference

Parameters
  • numNCEPerThread: Number of NCE per thread

int getNumInferenceThreads()

How many inference threads will be used to run the network

Return

Number of threads, 0, 1 or 2. Zero means AUTO

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 5, {{DatatypeEnum::Buffer, true}}}

Input message with data to be infered upon Default queue is blocking with size 5

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::NNData, false}}}

Outputs NNData message that carries inference results

Output passthrough = {*this, "passthrough", Output::Type::MSender, {{DatatypeEnum::Buffer, true}}}

Passthrough message on which the inference was performed.

Suitable for when input queue is set to non-blocking behavior.

class ObjectTracker : public dai::Node
#include <ObjectTracker.hpp>

ObjectTracker node. Performs object tracking using Kalman filter and hungarian algorithm.

Public Functions

void setTrackerThreshold(float threshold)

Specify tracker threshold.

Parameters
  • threshold: Above this threshold the detected objects will be tracked. Default 0, all image detections are tracked.

void setMaxObjectsToTrack(std::int32_t maxObjectsToTrack)

Specify maximum number of object to track.

Parameters
  • maxObjectsToTrack: Maximum number of object to track. Maximum 60.

void setDetectionLabelsToTrack(std::vector<std::uint32_t> labels)

Specify detection labels to track.

Parameters
  • labels: Detection labels to track. Default every label is tracked from image detection network output.

void setTrackerType(TrackerType type)

Specify tracker type algorithm.

Parameters
  • type: Tracker type.

void setTrackerIdAssigmentPolicy(TrackerIdAssigmentPolicy type)

Specify tracker ID assigment policy.

Parameters
  • type: Tracker ID assigment policy.

Public Members

Input inputTrackerFrame = {*this, "inputTrackerFrame", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ImgFrame, false}}}

Input ImgFrame message on which tracking will be performed. RGBp, BGRp, NV12, YUV420p types are supported. Default queue is non-blocking with size 4.

Input inputDetectionFrame = {*this, "inputDetectionFrame", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ImgFrame, false}}}

Input ImgFrame message on which object detection was performed. Default queue is non-blocking with size 4.

Input inputDetections = {*this, "inputDetections", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ImgDetections, true}}}

Input message with image detection from neural network. Default queue is non-blocking with size 4.

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::Tracklets, false}}}

Outputs Tracklets message that carries object tracking results.

Output passthroughTrackerFrame = {*this, "passthroughTrackerFrame", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message on which tracking was performed. Suitable for when input queue is set to non-blocking behavior.

Output passthroughDetectionFrame = {*this, "passthroughDetectionFrame", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message on which object detection was performed. Suitable for when input queue is set to non-blocking behavior.

Output passthroughDetections = {*this, "passthroughDetections", Output::Type::MSender, {{DatatypeEnum::ImgDetections, true}}}

Passthrough image detections message from neural nework output. Suitable for when input queue is set to non-blocking behavior.

class SpatialDetectionNetwork : public dai::node::DetectionNetwork
#include <SpatialDetectionNetwork.hpp>

SpatialDetectionNetwork node. Runs a neural inference on input image and calculates spatial location data.

Subclassed by dai::node::MobileNetSpatialDetectionNetwork, dai::node::YoloSpatialDetectionNetwork

Public Functions

std::string getName() const override

Retrieves nodes name.

std::vector<Input> getInputs() override

Retrieves all nodes inputs.

std::vector<Output> getOutputs() override

Retrieves all nodes outputs.

void setBoundingBoxScaleFactor(float scaleFactor)

Specifies scale factor for detected bounding boxes.

Parameters
  • scaleFactor: Scale factor must be in the interval (0,1].

void setDepthLowerThreshold(uint32_t lowerThreshold)

Specifies lower threshold in milimeters for depth values which will used to calculate spatial data

Parameters
  • lowerThreshold: LowerThreshold must be in the interval [0,upperThreshold] and less than upperThreshold.

void setDepthUpperThreshold(uint32_t upperThreshold)

Specifies upper threshold in milimeters for depth values which will used to calculate spatial data

Parameters
  • upperThreshold: UpperThreshold must be in the interval (lowerThreshold,65535].

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 5, {{DatatypeEnum::ImgFrame, false}}}

Input message with data to be infered upon Default queue is blocking with size 5

Input inputDepth = {*this, "inputDepth", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ImgFrame, false}}}

Input message with depth data used to retrieve spatial information about detected object Default queue is non-blocking with size 4

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::SpatialImgDetections, false}}}

Outputs ImgDetections message that carries parsed detection results.

Output boundingBoxMapping = {*this, "boundingBoxMapping", Output::Type::MSender, {{DatatypeEnum::SpatialLocationCalculatorConfig, false}}}

Outputs mapping of detected bounding boxes relative to depth map

Suitable for when displaying remapped bounding boxes on depth frame

Output passthrough = {*this, "passthrough", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough message on which the inference was performed.

Suitable for when input queue is set to non-blocking behavior.

Output passthroughDepth = {*this, "passthroughDepth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough message for depth frame on which the spatial location calculation was performed.

Suitable for when input queue is set to non-blocking behavior.

class SpatialLocationCalculator : public dai::Node
#include <SpatialLocationCalculator.hpp>

SpatialLocationCalculator node. Calculates spatial location data on a set of ROIs on depth map.

Public Functions

void setWaitForConfigInput(bool wait)

Specify whether or not wait until configuration message arrives to inputConfig Input.

Parameters
  • wait: True to wait for configuration message, false otherwise.

Public Members

SpatialLocationCalculatorConfig initialConfig

Initial config to use when calculating spatial location data.

Input inputConfig = {*this, "inputConfig", Input::Type::SReceiver, false, 4, {{DatatypeEnum::SpatialLocationCalculatorConfig, false}}}

Input SpatialLocationCalculatorConfig message with ability to modify parameters in runtime. Default queue is non-blocking with size 4.

Input inputDepth = {*this, "inputDepth", Input::Type::SReceiver, false, 4, {{DatatypeEnum::ImgFrame, false}}}

Input message with depth data used to retrieve spatial information about detected object. Default queue is non-blocking with size 4.

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::SpatialLocationCalculatorData, false}}}

Outputs SpatialLocationCalculatorData message that carries spatial location results.

Output passthroughDepth = {*this, "passthroughDepth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough message on which the calculation was performed. Suitable for when input queue is set to non-blocking behavior.

class SPIOut : public dai::Node
#include <SPIOut.hpp>

SPIOut node. Sends messages over SPI.

Public Functions

void setStreamName(std::string name)

Specifies stream name over which the node will send data

Parameters
  • name: Stream name

void setBusId(int id)

Specifies SPI Bus number to use

Parameters
  • id: SPI Bus id

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 8, {{DatatypeEnum::Buffer, true}}}

Input for any type of messages to be transfered over SPI stream

Default queue is blocking with size 8

class StereoDepth : public dai::Node
#include <StereoDepth.hpp>

StereoDepth node. Compute stereo disparity and depth from left-right image pair.

Public Functions

void loadCalibrationFile(const std::string &path)

Specify local filesystem path to the calibration file

Parameters
  • path: Path to calibration file. If empty use EEPROM

void loadCalibrationData(const std::vector<std::uint8_t> &data)

Specify calibration data as a vector of bytes

Parameters
  • path: Calibration data. If empty use EEPROM

void setEmptyCalibration()

Specify that a passthrough/dummy calibration should be used, when input frames are already rectified (e.g. sourced from recordings on the host)

void setInputResolution(int width, int height)

Specify input resolution size

Optional if MonoCamera exists, otherwise necessary

void setMedianFilter(Properties::MedianFilter median)

Parameters
  • median: Set kernel size for disparity/depth median filtering, or disable

void setDepthAlign(Properties::DepthAlign align)

Parameters
  • align: Set the disparity/depth alignment: centered (between the ‘left’ and ‘right’ inputs), or from the perspective of a rectified output stream

void setDepthAlign(CameraBoardSocket camera)

Parameters
  • camera: Set the camera from whose perspective the disparity/depth will be aligned

void setConfidenceThreshold(int confThr)

Confidence threshold for disparity calculation

Parameters
  • confThr: Confidence threshold value 0..255

void setLeftRightCheck(bool enable)

Computes and combines disparities in both L-R and R-L directions, and combine them.

For better occlusion handling, discarding invalid disparity values

void setSubpixel(bool enable)

Computes disparity with sub-pixel interpolation (5 fractional bits).

Suitable for long range. Currently incompatible with extended disparity

void setExtendedDisparity(bool enable)

Disparity range increased from 0-95 to 0-190, combined from full resolution and downscaled images.

Suitable for short range objects. Currently incompatible with sub-pixel disparity

void setRectifyEdgeFillColor(int color)

Fill color for missing data at frame edges

Parameters
  • color: Grayscale 0..255, or -1 to replicate pixels

void setRectifyMirrorFrame(bool enable)

Mirror rectified frames, only when LR-check mode is disabled. Default 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:

  • LR-check disabled: false: mapped to left and mirrored, true: mapped to right;

  • LR-check enabled: false: mapped to right, true: mapped to left, never mirrored.

Parameters
  • enable: True for normal disparity/depth, otherwise mirrored

void setOutputRectified(bool enable)

Enable outputting rectified frames. Optimizes computation on device side when disabled. DEPRECATED. The outputs are auto-enabled if used

void setOutputDepth(bool enable)

Enable outputting ‘depth’ stream (converted from disparity). In certain configurations, this will disable ‘disparity’ stream. DEPRECATED. The output is auto-enabled if used

Public Members

Input left = {*this, "left", Input::Type::SReceiver, false, 8, {{DatatypeEnum::ImgFrame, true}}}

Input for left ImgFrame of left-right pair

Default queue is non-blocking with size 8

Input right = {*this, "right", Input::Type::SReceiver, false, 8, {{DatatypeEnum::ImgFrame, true}}}

Input for right ImgFrame of left-right pair

Default queue is non-blocking with size 8

Output depth = {*this, "depth", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW16 encoded (0..65535) depth data in millimeters.

Non-determined / invalid depth values are set to 0

Output disparity = {*this, "disparity", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

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 (0..3040) for subpixel disparity mode (32 subpixel levels on top of standard mode).

Output syncedLeft = {*this, "syncedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message from ‘left’ Input.

Output syncedRight = {*this, "syncedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Passthrough ImgFrame message from ‘right’ Input.

Output rectifiedLeft = {*this, "rectifiedLeft", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

Output rectifiedRight = {*this, "rectifiedRight", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries RAW8 encoded (grayscale) rectified frame data.

class SystemLogger : public dai::Node
#include <SystemLogger.hpp>

SystemLogger node. Send system information periodically.

Public Functions

void setRate(float hz)

Specify logging rate, at which messages will be sent to out output

Parameters
  • hz: Sending rate in hertz (messages per second)

Public Members

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::SystemInformation, false}}}

Outputs SystemInformation message that carries various system information like memory and CPU usage, temperatures, …

class VideoEncoder : public dai::Node
#include <VideoEncoder.hpp>

VideoEncoder node. Encodes frames into MJPEG, H264 or H265.

Public Functions

void setDefaultProfilePreset(int width, int height, float fps, Properties::Profile profile)

Sets a default preset based on specified input size, frame rate and profile

Parameters
  • width: Input frame width

  • height: Input frame height

  • fps: Frame rate in frames per second

  • profile: Encoding profile

void setDefaultProfilePreset(std::tuple<int, int> size, float fps, Properties::Profile profile)

Sets a default preset based on specified input size, frame rate and profile

Parameters
  • size: Input frame size

  • fps: Frame rate in frames per second

  • profile: Encoding profile

void setNumFramesPool(int frames)

Set number of frames in pool

Parameters
  • frames: Number of pool frames

int getNumFramesPool() const

Get number of frames in pool

Return

Number of pool frames

void setRateControlMode(Properties::RateControlMode mode)

Set rate control mode.

void setProfile(std::tuple<int, int> size, Properties::Profile profile)

Set encoding profile.

void setProfile(int width, int height, Properties::Profile profile)

Set encoding profile.

void setBitrate(int bitrate)

Set output bitrate in bps. Final bitrate depends on rate control mode.

void setBitrateKbps(int bitrateKbps)

Set output bitrate in kbps. Final bitrate depends on rate control mode.

void setKeyframeFrequency(int freq)

Set keyframe frequency. Every Nth frame a keyframe is inserted.

Applicable only to H264 and H265 profiles

Examples:

  • 30 FPS video, keyframe frequency: 30. Every 1s a keyframe will be inserted

  • 60 FPS video, keyframe frequency: 180. Every 3s a keyframe will be inserted

void setNumBFrames(int numBFrames)

Set number of B frames to be inserted.

void setQuality(int quality)

Set quality

Parameters
  • quality: Value between 0-100%. Approximates quality

void setLossless(bool lossless)

Set lossless mode. Applies only to [M]JPEG profile

Parameters
  • lossless: True to enable lossless jpeg encoding, false otherwise

void setFrameRate(float frameRate)

Sets expected frame rate

Parameters
  • frameRate: Frame rate in frames per second

Properties::RateControlMode getRateControlMode() const

Get rate control mode.

Properties::Profile getProfile() const

Get profile.

int getBitrate() const

Get bitrate in bps.

int getBitrateKbps() const

Get bitrate in kbps.

int getKeyframeFrequency() const

Get keyframe frequency.

int getNumBFrames() const

Get number of B frames.

int getQuality() const

Get quality.

std::tuple<int, int> getSize() const

Get input size.

int getWidth() const

Get input width.

int getHeight() const

Get input height.

float getFrameRate() const

Get frame rate.

bool getLossless() const

Get lossless mode. Applies only when using [M]JPEG profile.

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 4, {{DatatypeEnum::ImgFrame, true}}}

Input for NV12 ImgFrame to be encoded Default queue is blocking with size set by ‘setNumFramesPool’ (4).

Output bitstream = {*this, "bitstream", Output::Type::MSender, {{DatatypeEnum::ImgFrame, false}}}

Outputs ImgFrame message that carries BITSTREAM encoded (MJPEG, H264 or H265) frame data.

class XLinkIn : public dai::Node
#include <XLinkIn.hpp>

XLinkIn node. Receives messages over XLink.

Public Functions

void setStreamName(const std::string &name)

Specifies XLink stream name to use.

The name should not start with double underscores ‘__’, as those are reserved for internal use.

Parameters
  • name: Stream name

void setMaxDataSize(std::uint32_t maxDataSize)

Set maximum message size it can receive

Parameters
  • maxDataSize: Maximum size in bytes

void setNumFrames(std::uint32_t numFrames)

Set number of frames in pool for sending messages forward

Parameters
  • numFrames: Maximum number of frames in pool

std::string getStreamName() const

Get stream name.

std::uint32_t getMaxDataSize() const

Get maximum messages size in bytes.

std::uint32_t getNumFrames() const

Get number of frames in pool.

Public Members

Output out = {*this, "out", Output::Type::MSender, {{DatatypeEnum::Buffer, true}}}

Outputs message of same type as send from host.

class XLinkOut : public dai::Node
#include <XLinkOut.hpp>

XLinkOut node. Sends messages over XLink.

Public Functions

void setStreamName(const std::string &name)

Specifies XLink stream name to use.

The name should not start with double underscores ‘__’, as those are reserved for internal use.

Parameters
  • name: Stream name

void setFpsLimit(float fps)

Specifies a message sending limit. It’s approximated from specified rate.

Parameters
  • fps: Approximate rate limit in messages per second

void setMetadataOnly(bool metadataOnly)

Specify whether to transfer only messages attributes and not buffer data

std::string getStreamName() const

Get stream name.

float getFpsLimit() const

Get rate limit in messages per second.

bool getMetadataOnly() const

Get whether to transfer only messages attributes and not buffer data.

Public Members

Input input = {*this, "in", Input::Type::SReceiver, true, 8, {{DatatypeEnum::Buffer, true}}}

Input for any type of messages to be transfered over XLink stream

Default queue is blocking with size 8

class YoloDetectionNetwork : public dai::node::DetectionNetwork
#include <DetectionNetwork.hpp>

YoloDetectionNetwork node. Parses Yolo results.

Public Functions

void setNumClasses(const int numClasses)

Set num classes.

void setCoordinateSize(const int coordinates)

Set coordianate size.

void setAnchors(std::vector<float> anchors)

Set anchors.

void setAnchorMasks(std::map<std::string, std::vector<int>> anchorMasks)

Set anchor masks.

void setIouThreshold(float thresh)

Set Iou threshold.

class YoloSpatialDetectionNetwork : public dai::node::SpatialDetectionNetwork
#include <SpatialDetectionNetwork.hpp>

YoloSpatialDetectionNetwork. (tiny)Yolov3/v4 based network with spatial location data.

Public Functions

void setNumClasses(const int numClasses)

Set num classes.

void setCoordinateSize(const int coordinates)

Set coordianate size.

void setAnchors(std::vector<float> anchors)

Set anchors.

void setAnchorMasks(std::map<std::string, std::vector<int>> anchorMasks)

Set anchor masks.

void setIouThreshold(float thresh)

Set Iou threshold.

Got questions?

We’re always happy to help with code or other questions you might have.