C++ API Reference¶
-
namespace
dai
¶ Typedefs
-
using
Clock
= std::chrono::steady_clock¶
Enums
-
enum
CameraExposureOffset
¶ Describe possible exposure offsets
Values:
-
enumerator
START
¶
-
enumerator
MIDDLE
¶
-
enumerator
END
¶
-
enumerator
-
enum
CameraBoardSocket
¶ Which Camera socket to use.
AUTO denotes that the decision will be made by device
Values:
-
enumerator
AUTO
¶
-
enumerator
CAM_A
¶
-
enumerator
CAM_B
¶
-
enumerator
CAM_C
¶
-
enumerator
CAM_D
¶
-
enumerator
CAM_E
¶
-
enumerator
CAM_F
¶
-
enumerator
CAM_G
¶
-
enumerator
CAM_H
¶
-
enumerator
CAM_I
¶
-
enumerator
CAM_J
¶
-
enumerator
RGB
¶
-
enumerator
CENTER
¶
-
enumerator
LEFT
¶
-
enumerator
RIGHT
¶
-
enumerator
-
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
¶
-
enumerator
-
enum
CameraModel
¶ Which CameraModel to initialize the calibration with.
Values:
-
enumerator
Perspective
¶
-
enumerator
Fisheye
¶
-
enumerator
Equirectangular
¶
-
enumerator
RadialDivision
¶
-
enumerator
-
enum
CameraSensorType
¶ Camera sensor type.
Values:
-
enumerator
AUTO
¶
-
enumerator
COLOR
¶
-
enumerator
MONO
¶
-
enumerator
TOF
¶
-
enumerator
THERMAL
¶
-
enumerator
-
enum
Colormap
¶ Camera sensor type.
Values:
-
enumerator
NONE
¶
-
enumerator
TURBO
¶
-
enumerator
JET
¶
-
enumerator
STEREO_TURBO
¶
-
enumerator
STEREO_JET
¶
-
enumerator
-
enum
Interpolation
¶ Interpolation type
Values:
-
enumerator
AUTO
¶
-
enumerator
BILINEAR
¶
-
enumerator
BICUBIC
¶
-
enumerator
NEAREST_NEIGHBOR
¶
-
enumerator
BYPASS
¶
-
enumerator
DEFAULT
¶
-
enumerator
DEFAULT_DISPARITY_DEPTH
¶
-
enumerator
-
enum
MedianFilter
Median filter config
Values:
-
enumerator
MEDIAN_OFF
-
enumerator
KERNEL_3x3
-
enumerator
KERNEL_5x5
-
enumerator
KERNEL_7x7
-
enumerator
-
enum
ProcessorType
¶ On which processor the node will be placed
Enum specifying processor
Values:
-
enumerator
LEON_CSS
¶
-
enumerator
LEON_MSS
¶
-
enumerator
-
enum
UsbSpeed
¶ Get USB Speed
Values:
-
enumerator
UNKNOWN
¶
-
enumerator
LOW
¶
-
enumerator
FULL
¶
-
enumerator
HIGH
¶
-
enumerator
SUPER
¶
-
enumerator
SUPER_PLUS
¶
-
enumerator
-
enum
DatatypeEnum
¶ Values:
-
enumerator
Buffer
¶
-
enumerator
ImgFrame
¶
-
enumerator
EncodedFrame
¶
-
enumerator
NNData
¶
-
enumerator
ImageManipConfig
¶
-
enumerator
CameraControl
¶
-
enumerator
ImgDetections
¶
-
enumerator
SpatialImgDetections
¶
-
enumerator
SystemInformation
¶
-
enumerator
SpatialLocationCalculatorConfig
¶
-
enumerator
SpatialLocationCalculatorData
¶
-
enumerator
EdgeDetectorConfig
¶
-
enumerator
AprilTagConfig
¶
-
enumerator
AprilTags
¶
-
enumerator
Tracklets
¶
-
enumerator
IMUData
¶
-
enumerator
StereoDepthConfig
¶
-
enumerator
FeatureTrackerConfig
¶
-
enumerator
ImageAlignConfig
¶
-
enumerator
ToFConfig
¶
-
enumerator
PointCloudConfig
¶
-
enumerator
PointCloudData
¶
-
enumerator
TrackedFeatures
¶
-
enumerator
MessageGroup
¶
-
enumerator
-
enum
SpatialLocationCalculatorAlgorithm
¶ SpatialLocationCalculatorAlgorithm configuration modes
Contains calculation method used to obtain spatial locations.
Values:
-
enumerator
AVERAGE
¶
-
enumerator
MEAN
¶
-
enumerator
MIN
¶
-
enumerator
MAX
¶
-
enumerator
MODE
¶
-
enumerator
MEDIAN
¶
-
enumerator
-
enum
LogLevel
¶ Values:
-
enumerator
TRACE
¶
-
enumerator
DEBUG
¶
-
enumerator
INFO
¶
-
enumerator
WARN
¶
-
enumerator
ERR
¶
-
enumerator
CRITICAL
¶
-
enumerator
OFF
¶
-
enumerator
-
enum
IMUSensor
¶ Available IMU sensors. More details about each sensor can be found in the datasheet:
https://www.ceva-dsp.com/wp-content/uploads/2019/10/BNO080_085-Datasheet.pdf
Values:
-
enumerator
ACCELEROMETER_RAW
¶ Section 2.1.1
Acceleration of the device without any postprocessing, straight from the sensor. Units are [m/s^2]
-
enumerator
ACCELEROMETER
¶ Section 2.1.1
Acceleration of the device including gravity. Units are [m/s^2]
-
enumerator
LINEAR_ACCELERATION
¶ Section 2.1.1
Acceleration of the device with gravity removed. Units are [m/s^2]
-
enumerator
GRAVITY
¶ Section 2.1.1
Gravity. Units are [m/s^2]
-
enumerator
GYROSCOPE_RAW
¶ Section 2.1.2
The angular velocity of the device without any postprocessing, straight from the sensor. Units are [rad/s]
-
enumerator
GYROSCOPE_CALIBRATED
¶ Section 2.1.2
The angular velocity of the device. Units are [rad/s]
-
enumerator
GYROSCOPE_UNCALIBRATED
¶ Section 2.1.2
Angular velocity without bias compensation. Units are [rad/s]
-
enumerator
MAGNETOMETER_RAW
¶ Section 2.1.3
Magnetic field measurement without any postprocessing, straight from the sensor. Units are [uTesla]
-
enumerator
MAGNETOMETER_CALIBRATED
¶ Section 2.1.3
The fully calibrated magnetic field measurement. Units are [uTesla]
-
enumerator
MAGNETOMETER_UNCALIBRATED
¶ Section 2.1.3
The magnetic field measurement without hard-iron offset applied. Units are [uTesla]
-
enumerator
ROTATION_VECTOR
¶ Section 2.2
The rotation vector provides an orientation output that is expressed as a quaternion referenced to magnetic north and gravity. It is produced by fusing the outputs of the accelerometer, gyroscope and magnetometer. The rotation vector is the most accurate orientation estimate available. The magnetometer provides correction in yaw to reduce drift and the gyroscope enables the most responsive performance.
-
enumerator
GAME_ROTATION_VECTOR
¶ Section 2.2
The game rotation vector is an orientation output that is expressed as a quaternion with no specific reference for heading, while roll and pitch are referenced against gravity. It is produced by fusing the outputs of the accelerometer and the gyroscope (i.e. no magnetometer). The game rotation vector does not use the magnetometer to correct the gyroscopes drift in yaw. This is a deliberate omission (as specified by Google) to allow gaming applications to use a smoother representation of the orientation without the jumps that an instantaneous correction provided by a magnetic field update could provide. Long term the output will likely drift in yaw due to the characteristics of gyroscopes, but this is seen as preferable for this output versus a corrected output.
-
enumerator
GEOMAGNETIC_ROTATION_VECTOR
¶ Section 2.2
The geomagnetic rotation vector is an orientation output that is expressed as a quaternion referenced to magnetic north and gravity. It is produced by fusing the outputs of the accelerometer and magnetometer. The gyroscope is specifically excluded in order to produce a rotation vector output using less power than is required to produce the rotation vector of section 2.2.4. The consequences of removing the gyroscope are: Less responsive output since the highly dynamic outputs of the gyroscope are not used More errors in the presence of varying magnetic fields.
-
enumerator
ARVR_STABILIZED_ROTATION_VECTOR
¶ Section 2.2
Estimates of the magnetic field and the roll/pitch of the device can create a potential correction in the rotation vector produced. For applications (typically augmented or virtual reality applications) where a sudden jump can be disturbing, the output is adjusted to prevent these jumps in a manner that takes account of the velocity of the sensor system.
-
enumerator
ARVR_STABILIZED_GAME_ROTATION_VECTOR
¶ Section 2.2
While the magnetometer is removed from the calculation of the game rotation vector, the accelerometer itself can create a potential correction in the rotation vector produced (i.e. the estimate of gravity changes). For applications (typically augmented or virtual reality applications) where a sudden jump can be disturbing, the output is adjusted to prevent these jumps in a manner that takes account of the velocity of the sensor system. This process is called AR/VR stabilization.
-
enumerator
-
enum
TrackerType
¶ Values:
-
enumerator
SHORT_TERM_KCF
¶ Kernelized Correlation Filter tracking.
-
enumerator
SHORT_TERM_IMAGELESS
¶ Short term tracking without using image data.
-
enumerator
ZERO_TERM_IMAGELESS
¶ Ability to track the objects without accessing image data.
-
enumerator
ZERO_TERM_COLOR_HISTOGRAM
¶ Tracking using image data too.
-
enumerator
Functions
-
bool
initialize
()¶
-
bool
initialize
(std::string additionalInfo, bool installSignalHandler = true, void *javavm = nullptr)¶
-
bool
initialize
(const char *additionalInfo, bool installSignalHandler = true, void *javavm = nullptr)¶
-
bool
initialize
(void *javavm)¶
-
DEPTHAI_SERIALIZE_EXT
(CameraSensorConfig, width, height, minFps, maxFps, fov, type)¶
-
DEPTHAI_SERIALIZE_EXT
(ChipTemperature, css, mss, upa, dss, average)¶
-
DEPTHAI_SERIALIZE_EXT
(DetectionParserOptions, nnFamily, confidenceThreshold, classes, coordinates, anchors, anchorMasks, iouThreshold)¶
-
DEPTHAI_SERIALIZE_OPTIONAL_EXT
(EepromData, version, boardCustom, boardName, boardRev, boardConf, hardwareConf, productName, deviceName, batchName, batchTime, boardOptions, cameraData, stereoRectificationData, imuExtrinsics, housingExtrinsics, miscellaneousData, stereoUseSpecTranslation, stereoEnableDistortionCorrection, verticalCameraSocket)¶
-
DEPTHAI_SERIALIZE_EXT
(MemoryInfo, remaining, used, total)¶
-
DEPTHAI_SERIALIZE_EXT
(RotatedRect, center, size, angle)¶
-
DEPTHAI_SERIALIZE_EXT
(StereoRectification, rectifiedRotationLeft, rectifiedRotationRight, leftCameraSocket, rightCameraSocket)¶
-
DEPTHAI_SERIALIZE_EXT
(TensorInfo, order, dataType, numDimensions, dims, strides, name, offset)¶
-
bool
isDatatypeSubclassOf
(DatatypeEnum parent, DatatypeEnum children)¶
-
DEPTHAI_SERIALIZE_EXT
(AprilTag, id, hamming, decisionMargin, topLeft, topRight, bottomRight, bottomLeft)¶
-
DEPTHAI_SERIALIZE_EXT
(EdgeDetectorConfigData, sobelFilterHorizontalKernel, sobelFilterVerticalKernel)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUReportAccelerometer, x, y, z, sequence, accuracy, timestamp, tsDevice)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUReportGyroscope, x, y, z, sequence, accuracy, timestamp, tsDevice)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUReportMagneticField, x, y, z, sequence, accuracy, timestamp, tsDevice)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUReportRotationVectorWAcc, i, j, k, real, rotationVectorAccuracy, sequence, accuracy, timestamp, tsDevice)¶
-
DEPTHAI_SERIALIZE_EXT
(ImgDetection, label, confidence, xmin, ymin, xmax, ymax)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialImgDetection, label, confidence, xmin, ymin, xmax, ymax, spatialCoordinates, boundingBoxMapping)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialLocationCalculatorConfigThresholds, lowerThreshold, upperThreshold)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialLocationCalculatorConfigData, roi, depthThresholds, calculationAlgorithm, stepSize)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialLocations, config, depthAverage, depthMode, depthMedian, depthMin, depthMax, depthAveragePixelCount, spatialCoordinates)¶
-
DEPTHAI_SERIALIZE_EXT
(TrackedFeature, position, id, age, harrisScore, trackingError)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::USB, vid, pid, flashBootedVid, flashBootedPid, maxSpeed, productName, manufacturer)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::Network, mtu, xlinkTcpNoDelay)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::GPIO, mode, direction, level, pull, drive, schmitt, slewFast)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::UART, tmp)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::Camera, name, sensorType, orientation)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::IMU, bus, interrupt, wake, csGpio, boot, reset)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig::UVC, cameraName, width, height, frameType, enable)¶
-
DEPTHAI_SERIALIZE_EXT
(BoardConfig, usb, network, sysctl, watchdogTimeoutMs, watchdogInitialDelayMs, gpio, uart, pcieInternalClock, usb3PhyInternalClock, emmc, logPath, logSizeMax, logVerbosity, logDevicePrints, nonExclusiveMode, camera, imu, uvc)¶
-
DEPTHAI_SERIALIZE_EXT
(LogMessage, nodeIdName, level, time, colorRangeStart, colorRangeEnd, payload)¶
-
DEPTHAI_SERIALIZE_EXT
(NodeConnectionSchema, node1Id, node1OutputGroup, node1Output, node2Id, node2InputGroup, node2Input)¶
-
DEPTHAI_SERIALIZE_EXT
(NodeIoInfo, group, name, type, blocking, queueSize, waitForMessage, id)¶
-
DEPTHAI_SERIALIZE_EXT
(NodeObjInfo, id, name, properties, ioInfo)¶
-
DEPTHAI_SERIALIZE_EXT
(PipelineSchema, connections, globalProperties, nodes)¶
-
DEPTHAI_SERIALIZE_EXT
(AprilTagProperties, initialConfig, inputConfigSync)¶
-
DEPTHAI_SERIALIZE_EXT
(CameraProperties, initialControl, boardSocket, cameraName, imageOrientation, colorOrder, interleaved, fp16, previewHeight, previewWidth, videoWidth, videoHeight, stillWidth, stillHeight, resolutionWidth, resolutionHeight, fps, isp3aFps, sensorCropX, sensorCropY, previewKeepAspectRatio, ispScale, sensorType, numFramesPoolRaw, numFramesPoolIsp, numFramesPoolVideo, numFramesPoolPreview, numFramesPoolStill, warpMeshSource, warpMeshUri, warpMeshWidth, warpMeshHeight, calibAlpha, warpMeshStepWidth, warpMeshStepHeight, rawPacked)¶
-
DEPTHAI_SERIALIZE_EXT
(CastProperties, numFramesPool, outputType, scale, offset)¶
-
DEPTHAI_SERIALIZE_EXT
(ColorCameraProperties, initialControl, boardSocket, cameraName, imageOrientation, colorOrder, interleaved, fp16, previewHeight, previewWidth, videoWidth, videoHeight, stillWidth, stillHeight, resolution, fps, isp3aFps, sensorCropX, sensorCropY, previewKeepAspectRatio, ispScale, numFramesPoolRaw, numFramesPoolIsp, numFramesPoolVideo, numFramesPoolPreview, numFramesPoolStill, rawPacked)¶
-
DEPTHAI_SERIALIZE_EXT
(DetectionNetworkProperties, blobSize, blobUri, numFrames, numThreads, numNCEPerThread, parser)¶
-
DEPTHAI_SERIALIZE_EXT
(DetectionParserProperties, numFramesPool, networkInputs, parser)¶
-
DEPTHAI_SERIALIZE_EXT
(EdgeDetectorProperties, initialConfig, outputFrameSize, numFramesPool)¶
-
DEPTHAI_SERIALIZE_EXT
(FeatureTrackerProperties, initialConfig, numShaves, numMemorySlices)¶
-
DEPTHAI_SERIALIZE_EXT
(GlobalProperties, leonCssFrequencyHz, leonMssFrequencyHz, pipelineName, pipelineVersion, cameraTuningBlobSize, cameraTuningBlobUri, calibData, xlinkChunkSize, sippBufferSize, sippDmaBufferSize)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUSensorConfig, sensitivityEnabled, sensitivityRelative, changeSensitivity, reportRate, sensorId)¶
-
DEPTHAI_SERIALIZE_EXT
(IMUProperties, imuSensors, batchReportThreshold, maxBatchReports, enableFirmwareUpdate)¶
-
DEPTHAI_SERIALIZE_EXT
(ImageAlignProperties, initialConfig, numFramesPool, alignWidth, alignHeight, warpHwIds, interpolation, outKeepAspectRatio, numShaves)¶
-
DEPTHAI_SERIALIZE_EXT
(ImageManipProperties, initialConfig, outputFrameSize, numFramesPool, meshWidth, meshHeight, meshUri)¶
-
DEPTHAI_SERIALIZE_EXT
(MessageDemuxProperties, dummy)¶
-
DEPTHAI_SERIALIZE_EXT
(MonoCameraProperties, initialControl, boardSocket, cameraName, imageOrientation, resolution, fps, isp3aFps, numFramesPool, numFramesPoolRaw, rawPacked)¶
-
DEPTHAI_SERIALIZE_EXT
(NeuralNetworkProperties, blobSize, blobUri, numFrames, numThreads, numNCEPerThread)¶
-
DEPTHAI_SERIALIZE_EXT
(ObjectTrackerProperties, trackerThreshold, maxObjectsToTrack, detectionLabelsToTrack, trackerType, trackerIdAssignmentPolicy, trackingPerClass)¶
-
DEPTHAI_SERIALIZE_EXT
(PointCloudProperties, initialConfig, numFramesPool)¶
-
DEPTHAI_SERIALIZE_EXT
(SPIInProperties, streamName, busId, maxDataSize, numFrames)¶
-
DEPTHAI_SERIALIZE_EXT
(SPIOutProperties, streamName, busId)¶
-
DEPTHAI_SERIALIZE_EXT
(ScriptProperties, scriptUri, scriptName, processor)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialDetectionNetworkProperties, blobSize, blobUri, numFrames, numThreads, numNCEPerThread, parser, detectedBBScaleFactor, depthThresholds, calculationAlgorithm, stepSize)¶
-
DEPTHAI_SERIALIZE_EXT
(SpatialLocationCalculatorProperties, roiConfig)¶
-
DEPTHAI_SERIALIZE_EXT
(StereoDepthProperties, initialConfig, depthAlignCamera, enableRectification, rectifyEdgeFillColor, width, height, outWidth, outHeight, outKeepAspectRatio, mesh, enableRuntimeStereoModeSwitch, numFramesPool, numPostProcessingShaves, numPostProcessingMemorySlices, focalLengthFromCalibration, useHomographyRectification, baseline, focalLength, disparityToDepthUseSpecTranslation, rectificationUseSpecTranslation, depthAlignmentUseSpecTranslation, alphaScaling)¶
-
DEPTHAI_SERIALIZE_EXT
(SyncProperties, syncThresholdNs, syncAttempts)¶
-
DEPTHAI_SERIALIZE_EXT
(SystemLoggerProperties, rateHz)¶
-
DEPTHAI_SERIALIZE_EXT
(ToFProperties, initialConfig, numFramesPool, numShaves)¶
-
DEPTHAI_SERIALIZE_EXT
(UVCProperties, gpioInit, gpioStreamOn, gpioStreamOff)¶
-
DEPTHAI_SERIALIZE_EXT
(VideoEncoderProperties, bitrate, keyframeFrequency, maxBitrate, numBFrames, numFramesPool, outputFrameSize, profile, quality, lossless, rateCtrlMode, frameRate)¶
-
DEPTHAI_SERIALIZE_EXT
(WarpProperties, outputWidth, outputHeight, outputFrameSize, numFramesPool, meshWidth, meshHeight, meshUri, warpHwIds, interpolation)¶
-
DEPTHAI_SERIALIZE_EXT
(XLinkInProperties, streamName, maxDataSize, numFrames)¶
-
DEPTHAI_SERIALIZE_EXT
(XLinkOutProperties, maxFpsLimit, streamName, metadataOnly)¶
Variables
-
static constexpr uint32_t
BOARD_CONFIG_MAGIC1
= 0x78010000U¶
-
static constexpr uint32_t
BOARD_CONFIG_MAGIC2
= 0x21ea17e6U¶
-
constexpr const char *
LOG_DEFAULT_PATTERN
= "[%E.%e] [%n] [%^%l%$] %v"¶
-
static constexpr auto
DEFAULT_SERIALIZATION_TYPE
= SerializationType::LIBNOP¶
-
class
ADatatype
¶ - #include <ADatatype.hpp>
Abstract message.
Subclassed by dai::Buffer
-
struct
AprilTag
¶ - #include <RawAprilTags.hpp>
AprilTag structure.
Public Members
-
int
id
= 0¶ The decoded ID of the tag
-
int
hamming
= 0¶ How many error bits were corrected? Note: accepting large numbers of corrected errors leads to greatly increased false positive rates. As of this implementation, the detector cannot detect tags with a hamming distance greater than 2.
-
float
decisionMargin
= 0.f¶ A measure of the quality of the binary decoding process; the average difference between the intensity of a data bit versus the decision threshold. Higher numbers roughly indicate better decodes. This is a reasonable measure of detection accuracy only for very small tags not effective for larger tags (where we could have sampled anywhere within a bit cell and still gotten a good detection.
-
int
-
class
AprilTagConfig
: public dai::Buffer - #include <AprilTagConfig.hpp>
AprilTagConfig message.
Public Functions
-
AprilTagConfig
()¶ Construct AprilTagConfig message.
-
AprilTagConfig &
setFamily
(Family family)¶ - Parameters
family
: AprilTag family
-
AprilTagConfig &
set
(dai::RawAprilTagConfig config)¶ Set explicit configuration.
- Parameters
config
: Explicit configuration
-
dai::RawAprilTagConfig
get
() const¶ Retrieve configuration data for AprilTag.
- Return
config for stereo depth algorithm
-
-
struct
AprilTagProperties
: public dai::PropertiesSerializable<Properties, AprilTagProperties>¶ - #include <AprilTagProperties.hpp>
Specify properties for AprilTag
Public Members
-
bool
inputConfigSync
= false¶ Whether to wait for config at ‘inputConfig’ IO.
-
bool
-
class
AprilTags
: public dai::Buffer - #include <AprilTags.hpp>
AprilTags message.
Public Functions
-
AprilTags &
setTimestamp
(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp)¶ Sets image timestamp related to dai::Clock::now()
-
AprilTags &
-
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
Adds all assets in an array to the AssetManager
- Parameters
assets
: Vector of assets to add
-
std::shared_ptr<dai::Asset>
set
(Asset asset)¶ Adds or overwrites an asset object to AssetManager.
- Return
Shared pointer to asset
- Parameters
asset
: Asset to add
-
std::shared_ptr<dai::Asset>
set
(const std::string &key, Asset asset)¶ Adds or overwrites an asset object to AssetManager with a specified key. Key value will be assigned to an Asset as well
- Return
Shared pointer to asset
- Parameters
key
: Key under which the asset should be storedasset
: Asset to store
-
std::shared_ptr<dai::Asset>
set
(const std::string &key, const dai::Path &path, int alignment = 64)¶ Loads file into asset manager under specified key.
- Parameters
key
: Key under which the asset should be storedpath
: Path to file which to load as assetalignment
: [Optional] alignment of asset data in asset storage. Default is 64B
-
std::shared_ptr<dai::Asset>
set
(const std::string &key, const std::vector<std::uint8_t> &data, int alignment = 64)¶ Loads file into asset manager under specified key.
- Return
Shared pointer to asset
- Parameters
key
: Key under which the asset should be storeddata
: Asset dataalignment
: [Optional] alignment of asset data in asset storage. Default is 64B
-
std::shared_ptr<const Asset>
get
(const std::string &key) const¶ - Return
Asset assigned to the specified key or a nullptr otherwise
-
std::shared_ptr<Asset>
get
(const std::string &key)¶ - Return
Asset assigned to the specified key or a nullptr 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
(AssetsMutable &assets, std::vector<std::uint8_t> &assetStorage, std::string prefix = "") const¶ Serializes.
-
class
Assets
¶ Subclassed by dai::AssetsMutable
-
struct
AssetView
¶
-
struct
BoardConfig
¶ Public Members
-
std::vector<std::string>
sysctl
¶ Optional list of FreeBSD sysctl parameters to be set (system, network, etc.). For example: “net.inet.tcp.delayed_ack=0” (this one is also set by default)
-
tl::optional<uint32_t>
watchdogTimeoutMs
¶ Watchdog config.
-
tl::optional<bool>
pcieInternalClock
¶ PCIe config.
-
tl::optional<bool>
usb3PhyInternalClock
¶ USB3 phy config.
-
tl::optional<bool>
mipi4LaneRgb
¶ MIPI 4Lane RGB config.
-
tl::optional<bool>
emmc
¶ eMMC config
-
tl::optional<std::string>
logPath
¶ log path
-
tl::optional<size_t>
logSizeMax
¶ Max log size.
-
tl::optional<bool>
logDevicePrints
¶ log device prints
-
struct
IMU
¶
-
struct
Network
¶ - #include <BoardConfig.hpp>
Network configuration.
Public Members
-
uint16_t
mtu
= 0¶ Network MTU, 0 is auto (usually 1500 for Ethernet) or forwarded from bootloader (not yet implemented there). Note: not advised to increase past 1500 for now
-
bool
xlinkTcpNoDelay
= true¶ Sets the
TCP_NODELAY
option for XLink TCP sockets (disable Nagle’s algorithm), reducing latency at the expense of a small hit for max throughput. Default istrue
-
uint16_t
-
std::vector<std::string>
-
class
Buffer
: public dai::ADatatype - #include <Buffer.hpp>
Base message - buffer of binary data.
Subclassed by dai::AprilTagConfig, dai::AprilTags, dai::CameraControl, dai::EdgeDetectorConfig, dai::EncodedFrame, dai::FeatureTrackerConfig, dai::ImageAlignConfig, dai::ImageManipConfig, dai::ImgDetections, dai::ImgFrame, dai::IMUData, dai::MessageGroup, dai::NNData, dai::PointCloudConfig, dai::PointCloudData, dai::SpatialImgDetections, dai::SpatialLocationCalculatorConfig, dai::SpatialLocationCalculatorData, dai::StereoDepthConfig, dai::SystemInformation, dai::ToFConfig, dai::TrackedFeatures, dai::Tracklets
Public Functions
-
Buffer
() Creates Buffer message.
-
std::vector<std::uint8_t> &
getData
() const Get non-owning reference to internal buffer.
- Return
Reference to internal buffer
-
void
setData
(const std::vector<std::uint8_t> &data) - Parameters
data
: Copies data to internal buffer
-
void
setData
(std::vector<std::uint8_t> &&data) - Parameters
data
: Moves data to internal buffer
-
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration>
getTimestamp
() const Retrieves timestamp related to dai::Clock::now()
-
std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration>
getTimestampDevice
() const Retrieves timestamp directly captured from device’s monotonic clock, not synchronized to host time. Used mostly for debugging
-
int64_t
getSequenceNum
() const Retrieves sequence number
-
Buffer &
setTimestamp
(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp) Sets timestamp related to dai::Clock::now()
-
Buffer &
setTimestampDevice
(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> timestamp) Sets timestamp related to dai::Clock::now()
-
Buffer &
setSequenceNum
(int64_t sequenceNum) Retrieves sequence number
-
-
class
CalibrationHandler
¶ - #include <CalibrationHandler.hpp>
CalibrationHandler is an interface to read/load/write structured calibration and device data. The following fields are protected and aren’t allowed to be overridden by default:
boardName
boardRev
boardConf
hardwareConf
batchName
batchTime
boardOptions
productName
Public Functions
-
CalibrationHandler
(dai::Path eepromDataPath)¶ Construct a new Calibration Handler object using the eeprom json file created from calibration procedure.
- Parameters
eepromDataPath
: takes the full path to the json file containing the calibration and device info.
-
CalibrationHandler
(dai::Path calibrationDataPath, dai::Path boardConfigPath)¶ Construct a new Calibration Handler object using the board config json file and .calib binary files created using gen1 calibration.
-
CalibrationHandler
(EepromData eepromData)¶ Construct a new Calibration Handler object from EepromData object.
- Parameters
eepromData
: EepromData data structure containing the calibration data.
-
dai::EepromData
getEepromData
() const¶ Get the Eeprom Data object
- Return
EepromData object which contains the raw calibration data
-
std::vector<std::vector<float>>
getCameraIntrinsics
(CameraBoardSocket cameraId, int resizeWidth = -1, int resizeHeight = -1, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const¶ Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.
- Parameters
cameraId
: Uses the cameraId to identify which camera intrinsics to returnresizewidth
: resized width of the image for which intrinsics is requested. resizewidth = -1 represents width is same as default intrinsicsresizeHeight
: resized height of the image for which intrinsics is requested. resizeHeight = -1 represents height is same as default intrinsicstopLeftPixelId
: (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagebottomRightPixelId
: (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagekeepAspectRatio
: Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
-
std::vector<std::vector<float>>
getCameraIntrinsics
(CameraBoardSocket cameraId, Size2f destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const¶ Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.
- Parameters
cameraId
: Uses the cameraId to identify which camera intrinsics to returndestShape
: resized width and height of the image for which intrinsics is requested.topLeftPixelId
: (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagebottomRightPixelId
: (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagekeepAspectRatio
: Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
-
std::vector<std::vector<float>>
getCameraIntrinsics
(CameraBoardSocket cameraId, std::tuple<int, int> destShape, Point2f topLeftPixelId = Point2f(), Point2f bottomRightPixelId = Point2f(), bool keepAspectRatio = true) const¶ Get the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Represents the 3x3 intrinsics matrix of the respective camera at the requested size and crop dimensions.
- Parameters
cameraId
: Uses the cameraId to identify which camera intrinsics to returndestShape
: resized width and height of the image for which intrinsics is requested.topLeftPixelId
: (x, y) point represents the top left corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagebottomRightPixelId
: (x, y) point represents the bottom right corner coordinates of the cropped image which is used to modify the intrinsics for the respective cropped imagekeepAspectRatio
: Enabling this will scale on width or height depending on which provides the max resolution and crops the remaining part of the other side
-
std::tuple<std::vector<std::vector<float>>, int, int>
getDefaultIntrinsics
(CameraBoardSocket cameraId) const¶ Get the Default Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Represents the 3x3 intrinsics matrix of the respective camera along with width and height at which it was calibrated.
- Parameters
cameraId
: Uses the cameraId to identify which camera intrinsics to return
-
std::vector<float>
getDistortionCoefficients
(CameraBoardSocket cameraId) const¶ Get the Distortion Coefficients object
- Return
the distortion coefficients of the requested camera in this order: [k1,k2,p1,p2,k3,k4,k5,k6,s1,s2,s3,s4,tx,ty] for CameraModel::Perspective or [k1, k2, k3, k4] for CameraModel::Fisheye see https://docs.opencv.org/4.5.4/d9/d0c/group__calib3d.html for Perspective model (Rational Polynomial Model) see https://docs.opencv.org/4.5.4/db/d58/group__calib3d__fisheye.html for Fisheye model
- Parameters
cameraId
: Uses the cameraId to identify which distortion Coefficients to return.
-
float
getFov
(CameraBoardSocket cameraId, bool useSpec = true) const¶ Get the Fov of the camera
- Return
field of view of the camera with given cameraId.
- Parameters
cameraId
: of the camera of which we are fetching fov.useSpec
: Disabling this bool will calculate the fov based on intrinsics (focal length, image width), instead of getting it from the camera specs
-
uint8_t
getLensPosition
(CameraBoardSocket cameraId) const¶ Get the lens position of the given camera
- Return
lens position of the camera with given cameraId at which it was calibrated.
- Parameters
cameraId
: of the camera with lens position is requested.
-
CameraModel
getDistortionModel
(CameraBoardSocket cameraId) const¶ Get the distortion model of the given camera
- Return
lens position of the camera with given cameraId at which it was calibrated.
- Parameters
cameraId
: of the camera with lens position is requested.
-
std::vector<std::vector<float>>
getCameraExtrinsics
(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = false) const¶ Get the Camera Extrinsics object between two cameras from the calibration data if there is a linked connection between any two cameras then the relative rotation and translation (in centimeters) is returned by this function.
Matrix representation of transformation matrix
\[\begin{split} \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
a transformationMatrix which is 4x4 in homogeneous coordinate system
- Parameters
srcCamera
: Camera Id of the camera which will be considered as origin.dstCamera
: Camera Id of the destination camera to which we are fetching the rotation and translation from the SrcCamerauseSpecTranslation
: Enabling this bool uses the translation information from the board design data
-
std::vector<float>
getCameraTranslationVector
(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation = true) const¶ Get the Camera translation vector between two cameras from the calibration data.
- Return
a translation vector like [x, y, z] in centimeters
- Parameters
srcCamera
: Camera Id of the camera which will be considered as origin.dstCamera
: Camera Id of the destination camera to which we are fetching the translation vector from the SrcCamerauseSpecTranslation
: Disabling this bool uses the translation information from the calibration data (not the board design data)
-
float
getBaselineDistance
(CameraBoardSocket cam1 = CameraBoardSocket::CAM_C, CameraBoardSocket cam2 = CameraBoardSocket::CAM_B, bool useSpecTranslation = true) const¶ Get the baseline distance between two specified cameras. By default it will get the baseline between CameraBoardSocket.CAM_C and CameraBoardSocket.CAM_B.
- Return
baseline distance in centimeters
- Parameters
cam1
: First cameracam2
: Second camerauseSpecTranslation
: Enabling this bool uses the translation information from the board design data (not the calibration data)
-
std::vector<std::vector<float>>
getCameraToImuExtrinsics
(CameraBoardSocket cameraId, bool useSpecTranslation = false) const¶ Get the Camera To Imu Extrinsics object From the data loaded if there is a linked connection between IMU and the given camera then there relative rotation and translation from the camera to IMU is returned.
Matrix representation of transformation matrix
\[\begin{split} \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system
- Parameters
cameraId
: Camera Id of the camera which will be considered as origin. from which Transformation matrix to the IMU will be founduseSpecTranslation
: Enabling this bool uses the translation information from the board design data
-
std::vector<std::vector<float>>
getImuToCameraExtrinsics
(CameraBoardSocket cameraId, bool useSpecTranslation = false) const¶ Get the Imu To Camera Extrinsics object from the data loaded if there is a linked connection between IMU and the given camera then there relative rotation and translation from the IMU to Camera is returned.
Matrix representation of transformation matrix
\[\begin{split} \text{Transformation Matrix} = \left [ \begin{matrix} r_{00} & r_{01} & r_{02} & T_x \\ r_{10} & r_{11} & r_{12} & T_y \\ r_{20} & r_{21} & r_{22} & T_z \\ 0 & 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Return
Returns a transformationMatrix which is 4x4 in homogeneous coordinate system
- Parameters
cameraId
: Camera Id of the camera which will be considered as destination. To which Transformation matrix from the IMU will be found.useSpecTranslation
: Enabling this bool uses the translation information from the board design data
-
std::vector<std::vector<float>>
getStereoRightRectificationRotation
() const¶ Get the Stereo Right Rectification Rotation object
- Return
returns a 3x3 rectification rotation matrix
-
std::vector<std::vector<float>>
getStereoLeftRectificationRotation
() const¶ Get the Stereo Left Rectification Rotation object
- Return
returns a 3x3 rectification rotation matrix
-
dai::CameraBoardSocket
getStereoLeftCameraId
() const¶ Get the camera id of the camera which is used as left camera of the stereo setup
- Return
cameraID of the camera used as left camera
-
dai::CameraBoardSocket
getStereoRightCameraId
() const¶ Get the camera id of the camera which is used as right camera of the stereo setup
- Return
cameraID of the camera used as right camera
-
bool
eepromToJsonFile
(dai::Path destPath) const¶ Write raw calibration/board data to json file.
- Return
True on success, false otherwise
- Parameters
destPath
: Full path to the json file in which raw calibration data will be stored
-
nlohmann::json
eepromToJson
() const¶ Get JSON representation of calibration data
- Return
JSON structure
-
void
setBoardInfo
(std::string boardName, std::string boardRev)¶ Set the Board Info object
- Parameters
version
: Sets the version of the Calibration data(Current version is 6)boardName
: Sets your board name.boardRev
: set your board revision id.
-
void
setBoardInfo
(std::string productName, std::string boardName, std::string boardRev, std::string boardConf, std::string hardwareConf, std::string batchName, uint64_t batchTime, uint32_t boardOptions, std::string boardCustom = "")¶ Set the Board Info object. Creates version 7 EEPROM data
- Parameters
productName
: Sets product name (alias).boardName
: Sets board name.boardRev
: Sets board revision id.boardConf
: Sets board configuration id.hardwareConf
: Sets hardware configuration id.batchName
: Sets batch name.batchTime
: Sets batch time (unix timestamp).boardCustom
: Sets a custom board (Default empty string).
-
void
setBoardInfo
(std::string deviceName, std::string productName, std::string boardName, std::string boardRev, std::string boardConf, std::string hardwareConf, std::string batchName, uint64_t batchTime, uint32_t boardOptions, std::string boardCustom = "")¶ Set the Board Info object. Creates version 7 EEPROM data
- Parameters
deviceName
: Sets device name.productName
: Sets product name (alias).boardName
: Sets board name.boardRev
: Sets board revision id.boardConf
: Sets board configuration id.hardwareConf
: Sets hardware configuration id.batchName
: Sets batch name. Not supported anymorebatchTime
: Sets batch time (unix timestamp).boardCustom
: Sets a custom board (Default empty string).
-
void
setDeviceName
(std::string deviceName)¶ Set the deviceName which responses to getDeviceName of Device
- Parameters
deviceName
: Sets device name.
-
void
setProductName
(std::string productName)¶ Set the productName which acts as alisas for users to identify the device
- Parameters
productName
: Sets product name (alias).
-
void
setCameraIntrinsics
(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, Size2f frameSize)¶ Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters
cameraId
: CameraId of the camera for which Camera intrinsics are being loadedintrinsics
: 3x3 intrinsics matrixframeSize
: Represents the width and height of the image at which intrinsics are calculated.
-
void
setCameraIntrinsics
(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, int width, int height)¶ Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters
cameraId
: CameraId of the camera for which Camera intrinsics are being loadedintrinsics
: 3x3 intrinsics matrixwidth
: Represents the width of the image at which intrinsics are calculated.height
: Represents the height of the image at which intrinsics are calculated.
-
void
setCameraIntrinsics
(CameraBoardSocket cameraId, std::vector<std::vector<float>> intrinsics, std::tuple<int, int> frameSize)¶ Set the Camera Intrinsics object
Matrix representation of intrinsic matrix
\[\begin{split} \text{Intrinsic Matrix} = \left [ \begin{matrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{matrix} \right ] \end{split}\]- Parameters
cameraId
: CameraId of the camera for which Camera intrinsics are being loadedintrinsics
: 3x3 intrinsics matrixframeSize
: Represents the width and height of the image at which intrinsics are calculated.
-
void
setDistortionCoefficients
(CameraBoardSocket cameraId, std::vector<float> distortionCoefficients)¶ Sets the distortion Coefficients obtained from camera calibration
- Parameters
cameraId
: Camera Id of the camera for which distortion coefficients are computeddistortionCoefficients
: Distortion Coefficients of the respective Camera.
-
void
setFov
(CameraBoardSocket cameraId, float hfov)¶ Set the Fov of the Camera
- Parameters
cameraId
: Camera Id of the camerahfov
: Horizontal fov of the camera from Camera Datasheet
-
void
setLensPosition
(CameraBoardSocket cameraId, uint8_t lensPosition)¶ Sets the distortion Coefficients obtained from camera calibration
- Parameters
cameraId
: Camera Id of the cameralensPosition
: lens posiotion value of the camera at the time of calibration
-
void
setCameraType
(CameraBoardSocket cameraId, CameraModel cameraModel)¶ Set the Camera Type object
- Parameters
cameraId
: CameraId of the camera for which cameraModel Type is being updated.cameraModel
: Type of the model the camera represents
-
void
setCameraExtrinsics
(CameraBoardSocket srcCameraId, CameraBoardSocket destCameraId, std::vector<std::vector<float>> rotationMatrix, std::vector<float> translation, std::vector<float> specTranslation = {0, 0, 0})¶ Set the Camera Extrinsics object
- Parameters
srcCameraId
: Camera Id of the camera which will be considered as relative origin.destCameraId
: Camera Id of the camera which will be considered as destination from srcCameraId.rotationMatrix
: Rotation between srcCameraId and destCameraId origins.translation
: Translation between srcCameraId and destCameraId origins.specTranslation
: Translation between srcCameraId and destCameraId origins from the design.
-
void
setImuExtrinsics
(CameraBoardSocket destCameraId, std::vector<std::vector<float>> rotationMatrix, std::vector<float> translation, std::vector<float> specTranslation = {0, 0, 0})¶ Set the Imu to Camera Extrinsics object
- Parameters
destCameraId
: Camera Id of the camera which will be considered as destination from IMU.rotationMatrix
: Rotation between srcCameraId and destCameraId origins.translation
: Translation between IMU and destCameraId origins.specTranslation
: Translation between IMU and destCameraId origins from the design.
-
void
setStereoLeft
(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation)¶ Set the Stereo Left Rectification object
Homography of the Left Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_left)
- Parameters
cameraId
: CameraId of the camera which will be used as left Camera of stereo SetuprectifiedRotation
: Rectification rotation of the left camera required for feature matching
-
void
setStereoRight
(CameraBoardSocket cameraId, std::vector<std::vector<float>> rectifiedRotation)¶ Set the Stereo Right Rectification object
Homography of the Right Rectification = Intrinsics_right * rectifiedRotation * inv(Intrinsics_right)
- Parameters
cameraId
: CameraId of the camera which will be used as left Camera of stereo SetuprectifiedRotation
: Rectification rotation of the left camera required for feature matching
-
bool
validateCameraArray
() const¶ Using left camera as the head it iterates over the camera extrinsics connection to check if all the camera extrinsics are connected and no loop exists.
- Return
true on proper connection with no loops.
Public Static Functions
-
CalibrationHandler
fromJson
(nlohmann::json eepromDataJson)¶ Construct a new Calibration Handler object from JSON EepromData.
- Parameters
eepromDataJson
: EepromData as JSON
-
class
CallbackHandler
¶
-
class
CameraControl
: public dai::Buffer - #include <CameraControl.hpp>
CameraControl message. Specifies various camera control commands like:
Still capture
Auto/manual focus
Auto/manual white balance
Auto/manual exposure
Anti banding
…
By default the camera enables 3A, with auto-focus in
CONTINUOUS_VIDEO
mode, auto-white-balance inAUTO
mode, and auto-exposure with anti-banding for 50Hz mains frequency.Public Functions
-
CameraControl
() Construct CameraControl message.
-
CameraControl &
setCaptureStill
(bool capture) Set a command to capture a still image
-
CameraControl &
setStartStreaming
() Set a command to start streaming
-
CameraControl &
setStopStreaming
() Set a command to stop streaming
-
CameraControl &
setExternalTrigger
(int numFramesBurst, int numFramesDiscard) Set a command to enable external trigger snapshot mode
A rising edge on the sensor FSIN pin will make it capture a sequence of
numFramesBurst
frames. FirstnumFramesDiscard
will be skipped as configured (can be set to 0 as well), as they may have degraded quality
-
CameraControl &
setFrameSyncMode
(FrameSyncMode mode) Set the frame sync mode for continuous streaming operation mode, translating to how the camera pin FSIN/FSYNC is used: input/output/disabled
-
CameraControl &
setStrobeSensor
(int activeLevel = 1) Enable STROBE output on sensor pin, optionally configuring the polarity. Note: for many sensors the polarity is high-active and not configurable
-
CameraControl &
setStrobeExternal
(int gpioNumber, int activeLevel = 1) Enable STROBE output driven by a MyriadX GPIO, optionally configuring the polarity This normally requires a FSIN/FSYNC/trigger input for MyriadX (usually GPIO 41), to generate timings
-
CameraControl &
setStrobeDisable
() Disable STROBE output
-
CameraControl &
setAutoFocusMode
(AutoFocusMode mode) Set a command to specify autofocus mode. Default
CONTINUOUS_VIDEO
-
CameraControl &
setAutoFocusTrigger
() Set a command to trigger autofocus
-
CameraControl &
setAutoFocusLensRange
(int infinityPosition, int macroPosition) Set autofocus lens range,
infinityPosition < macroPosition
, valid values0..255
. May help to improve autofocus in case the lens adjustment is not typical/tuned
-
CameraControl &
setAutoFocusRegion
(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height) Set a command to specify focus region in pixels. Note: the region should be mapped to the configured sensor resolution, before ISP scaling
- Parameters
startX
: X coordinate of top left corner of regionstartY
: Y coordinate of top left corner of regionwidth
: Region widthheight
: Region height
-
CameraControl &
setManualFocus
(uint8_t lensPosition) Set a command to specify manual focus position
- Parameters
lensPosition
: specify lens position 0..255
-
CameraControl &
setManualFocusRaw
(float lensPositionRaw) Set a command to specify manual focus position (more precise control).
- Return
- Parameters
lensPositionRaw
: specify lens position 0.0f .. 1.0f
-
CameraControl &
setAutoExposureEnable
() Set a command to enable auto exposure
-
CameraControl &
setAutoExposureLock
(bool lock) Set a command to specify lock auto exposure
- Parameters
lock
: Auto exposure lock mode enabled or disabled
-
CameraControl &
setAutoExposureRegion
(uint16_t startX, uint16_t startY, uint16_t width, uint16_t height) Set a command to specify auto exposure region in pixels. Note: the region should be mapped to the configured sensor resolution, before ISP scaling
- Parameters
startX
: X coordinate of top left corner of regionstartY
: Y coordinate of top left corner of regionwidth
: Region widthheight
: Region height
-
CameraControl &
setAutoExposureCompensation
(int compensation) Set a command to specify auto exposure compensation
- Parameters
compensation
: Compensation value between -9..9, default 0
-
CameraControl &
setAutoExposureLimit
(uint32_t maxExposureTimeUs) Set a command to specify the maximum exposure time limit for auto-exposure. By default the AE algorithm prioritizes increasing exposure over ISO, up to around frame-time (subject to further limits imposed by anti-banding)
- Parameters
maxExposureTimeUs
: Maximum exposure time in microseconds
-
CameraControl &
setAutoExposureLimit
(std::chrono::microseconds maxExposureTime) Set a command to specify the maximum exposure time limit for auto-exposure. By default the AE algorithm prioritizes increasing exposure over ISO, up to around frame-time (subject to further limits imposed by anti-banding)
- Parameters
maxExposureTime
: Maximum exposure time
-
CameraControl &
setAntiBandingMode
(AntiBandingMode mode) Set a command to specify anti-banding mode. Anti-banding / anti-flicker works in auto-exposure mode, by controlling the exposure time to be applied in multiples of half the mains period, for example in multiple of 10ms for 50Hz (period 20ms) AC-powered illumination sources.
If the scene would be too bright for the smallest exposure step (10ms in the example, with ISO at a minimum of 100), anti-banding is not effective.
- Parameters
mode
: Anti-banding mode to use. Default:MAINS_50_HZ
-
CameraControl &
setManualExposure
(uint32_t exposureTimeUs, uint32_t sensitivityIso) Set a command to manually specify exposure
- Parameters
exposureTimeUs
: Exposure time in microsecondssensitivityIso
: Sensitivity as ISO value, usual range 100..1600
-
CameraControl &
setManualExposure
(std::chrono::microseconds exposureTime, uint32_t sensitivityIso) Set a command to manually specify exposure
- Parameters
exposureTime
: Exposure timesensitivityIso
: Sensitivity as ISO value, usual range 100..1600
-
CameraControl &
setAutoWhiteBalanceMode
(AutoWhiteBalanceMode mode) Set a command to specify auto white balance mode
- Parameters
mode
: Auto white balance mode to use. DefaultAUTO
-
CameraControl &
setAutoWhiteBalanceLock
(bool lock) Set a command to specify auto white balance lock
- Parameters
lock
: Auto white balance lock mode enabled or disabled
-
CameraControl &
setManualWhiteBalance
(int colorTemperatureK) Set a command to manually specify white-balance color correction
- Parameters
colorTemperatureK
: Light source color temperature in kelvins, range 1000..12000
-
CameraControl &
setBrightness
(int value) Set a command to adjust image brightness
- Parameters
value
: Brightness, range -10..10, default 0
-
CameraControl &
setContrast
(int value) Set a command to adjust image contrast
- Parameters
value
: Contrast, range -10..10, default 0
-
CameraControl &
setSaturation
(int value) Set a command to adjust image saturation
- Parameters
value
: Saturation, range -10..10, default 0
-
CameraControl &
setSharpness
(int value) Set a command to adjust image sharpness
- Parameters
value
: Sharpness, range 0..4, default 1
-
CameraControl &
setLumaDenoise
(int value) Set a command to adjust luma denoise amount
- Parameters
value
: Luma denoise amount, range 0..4, default 1
-
CameraControl &
setChromaDenoise
(int value) Set a command to adjust chroma denoise amount
- Parameters
value
: Chroma denoise amount, range 0..4, default 1
-
CameraControl &
setSceneMode
(SceneMode mode) Set a command to specify scene mode
- Parameters
mode
: Scene mode
-
CameraControl &
setEffectMode
(EffectMode mode) Set a command to specify effect mode
- Parameters
mode
: Effect mode
-
CameraControl &
setControlMode
(ControlMode mode) Set a command to specify control mode
- Parameters
mode
: Control mode
-
CameraControl &
setCaptureIntent
(CaptureIntent mode) Set a command to specify capture intent mode
- Parameters
mode
: Capture intent mode
-
bool
getCaptureStill
() const Check whether command to capture a still is set
- Return
True if capture still command is set
-
std::chrono::microseconds
getExposureTime
() const Retrieves exposure time
-
int
getSensitivity
() const Retrieves sensitivity, as an ISO value
-
int
getLensPosition
() const Retrieves lens position, range 0..255. Returns -1 if not available
-
float
getLensPositionRaw
() const Retrieves lens position, range 0.0f..1.0f.
-
CameraControl &
set
(dai::RawCameraControl config) Set explicit configuration.
- Parameters
config
: Explicit configuration
-
dai::RawCameraControl
get
() const Retrieve configuration data for CameraControl.
- Return
config for CameraControl
-
struct
CameraFeatures
¶ - #include <CameraFeatures.hpp>
CameraFeatures structure
Characterizes detected cameras on board
Public Members
-
CameraBoardSocket
socket
= CameraBoardSocket::AUTO¶ Board socket where the camera was detected
-
std::string
sensorName
¶ Camera sensor name, e.g: “IMX378”, “OV9282”
-
std::int32_t
width
= -1¶ Maximum sensor resolution
-
CameraImageOrientation
orientation
= CameraImageOrientation::AUTO¶ Default camera orientation, board dependent
-
std::vector<CameraSensorType>
supportedTypes
¶ List of supported types of processing for the given camera.
For some sensors it’s not possible to determine if they are color or mono (e.g. OV9782 and OV9282), so this could return more than one entry
-
bool
hasAutofocusIC
= false¶ Whether an autofocus VCM IC was detected
-
bool
hasAutofocus
= false¶ Whether camera has auto focus capabilities, or is a fixed focus lens
-
std::string
name
¶ Camera name or alias
-
std::vector<std::string>
additionalNames
¶ Additional camera names or aliases
-
std::vector<CameraSensorConfig>
configs
¶ Available sensor configs
-
tl::optional<CameraSensorConfig>
calibrationResolution
= tl::nullopt¶ The resolution which should be used for calibration.
-
CameraBoardSocket
-
struct
CameraInfo
¶ - #include <CameraInfo.hpp>
CameraInfo structure.
-
struct
CameraProperties
: public dai::PropertiesSerializable<Properties, CameraProperties>¶ - #include <CameraProperties.hpp>
Specify properties for ColorCamera such as camera ID, …
Public Types
Public Members
-
RawCameraControl
initialControl
¶ Initial controls applied to ColorCamera node
-
CameraBoardSocket
boardSocket
= CameraBoardSocket::AUTO¶ Which socket will color camera use
-
std::string
cameraName
= ""¶ Which camera name 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
= DEFAULT_PREVIEW_HEIGHT¶ Preview frame output height
-
uint32_t
previewWidth
= DEFAULT_PREVIEW_WIDTH¶ Preview frame output width
-
float
fps
= 30.0¶ Camera sensor FPS
-
int
isp3aFps
= 0¶ Isp 3A rate (auto focus, auto exposure, auto white balance, camera controls etc.). Default (0) matches the camera FPS, meaning that 3A is running on each frame. Reducing the rate of 3A reduces the CPU usage on CSS, but also increases the convergence rate of 3A. Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing.
-
bool
previewKeepAspectRatio
= false¶ Whether to keep aspect ratio of input (video/preview size) or not
-
CameraSensorType
sensorType
= CameraSensorType::AUTO¶ Type of sensor, specifies what kind of postprocessing is performed.
-
int
numFramesPoolRaw
= 3¶ Pool sizes
-
tl::optional<float>
calibAlpha
¶ Free scaling parameter between 0 (when all the pixels in the undistorted image are valid) and 1 (when all the source image pixels are retained in the undistorted image). On some high distortion lenses, and/or due to rectification (image rotated) invalid areas may appear even with alpha=0, in these cases alpha < 0.0 helps removing invalid areas. See getOptimalNewCameraMatrix from opencv for more details.
-
tl::optional<bool>
rawPacked
¶ Configures whether the camera
raw
frames are saved as MIPI-packed to memory. The packed format is more efficient, consuming less memory on device, and less data to send to host: RAW10: 4 pixels saved on 5 bytes, RAW12: 2 pixels saved on 3 bytes. When packing is disabled (false
), data is saved lsb-aligned, e.g. a RAW10 pixel will be stored as uint16, on bits 9..0: 0b0000’00pp’pppp’pppp. Default is auto: enabled for standard color/monochrome cameras where ISP can work with both packed/unpacked, but disabled for other cameras like ToF.
-
struct
IspScale
¶
-
RawCameraControl
-
struct
CameraSensorConfig
¶ - #include <CameraFeatures.hpp>
Sensor config
-
struct
CastProperties
: public dai::PropertiesSerializable<Properties, CastProperties>¶ - #include <CastProperties.hpp>
Specify properties for Cast
-
struct
ChipTemperature
¶ - #include <ChipTemperature.hpp>
Chip temperature information.
Multiple temperature measurement points and their average
-
struct
ColorCameraProperties
: public dai::PropertiesSerializable<Properties, ColorCameraProperties>¶ - #include <ColorCameraProperties.hpp>
Specify properties for ColorCamera such as camera ID, …
Public Types
-
enum
SensorResolution
¶ Select the camera sensor resolution
Values:
-
enumerator
THE_1080_P
¶ 1920 × 1080
-
enumerator
THE_4_K
¶ 3840 × 2160
-
enumerator
THE_12_MP
¶ 4056 × 3040
-
enumerator
THE_13_MP
¶ 4208 × 3120
-
enumerator
THE_720_P
¶ 1280 × 720
-
enumerator
THE_800_P
¶ 1280 × 800
-
enumerator
THE_1200_P
¶ 1920 × 1200
-
enumerator
THE_5_MP
¶ 2592 × 1944
-
enumerator
THE_4000X3000
¶ 4000 × 3000
-
enumerator
THE_5312X6000
¶ 5312 × 6000
-
enumerator
THE_48_MP
¶ 8000 × 6000
-
enumerator
THE_1440X1080
¶ 1440 × 1080
-
enumerator
THE_1352X1012
¶ 1352 × 1012
-
enumerator
THE_2024X1520
¶ 2024 × 1520
-
enumerator
Public Members
-
CameraBoardSocket
boardSocket
= CameraBoardSocket::AUTO¶ Which socket will color camera use
-
std::string
cameraName
= ""¶ Which camera name 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
-
SensorResolution
resolution
= SensorResolution::THE_1080_P¶ Select the camera sensor resolution
-
float
fps
= 30.0¶ Camera sensor FPS
-
int
isp3aFps
= 0¶ Isp 3A rate (auto focus, auto exposure, auto white balance, camera controls etc.). Default (0) matches the camera FPS, meaning that 3A is running on each frame. Reducing the rate of 3A reduces the CPU usage on CSS, but also increases the convergence rate of 3A. Note that camera controls will be processed at this rate. E.g. if camera is running at 30 fps, and camera control is sent at every frame, but 3A fps is set to 15, the camera control messages will be processed at 15 fps rate, which will lead to queueing.
-
bool
previewKeepAspectRatio
= true¶ Whether to keep aspect ratio of input (video size) or not
-
int
numFramesPoolRaw
= 3¶ Pool sizes
-
std::vector<dai::FrameEvent>
eventFilter
= {dai::FrameEvent::READOUT_START}¶ List of events to receive, the rest will be ignored
-
tl::optional<bool>
rawPacked
¶ Configures whether the camera
raw
frames are saved as MIPI-packed to memory. The packed format is more efficient, consuming less memory on device, and less data to send to host: RAW10: 4 pixels saved on 5 bytes, RAW12: 2 pixels saved on 3 bytes. When packing is disabled (false
), data is saved lsb-aligned, e.g. a RAW10 pixel will be stored as uint16, on bits 9..0: 0b0000’00pp’pppp’pppp. Default is auto: enabled for standard color/monochrome cameras where ISP can work with both packed/unpacked, but disabled for other cameras like ToF.
-
struct
IspScale
¶
-
enum
-
template<typename
T
>
classcopyable_unique_ptr
: public std::unique_ptr<T>¶ - #include <copyable_unique_ptr.hpp>
A smart pointer with deep copy semantics.
This is similar to
std::unique_ptr
in that it does not permit shared ownership of the contained object. However, unlikestd::unique_ptr
, copyable_unique_ptr supports copy and assignment operations, by insisting that the contained object be “copyable”. To be copyable, the class must have either an accessible copy constructor, or it must have an accessible clone method with signaturewhere Foo is the type of the managed object. By “accessible” we mean either that the copy constructor or clone method is public, orstd::unique_ptr<Foo> Clone() const;
friend copyable_unique_ptr<Foo>;
appears in Foo’s class declaration.Generally, the API is modeled as closely as possible on the C++ standard
std::unique_ptr
API and copyable_unique_ptr<T> is interoperable withunique_ptr<T>
wherever that makes sense. However, there are some differences:It always uses a default deleter.
There is no array version.
To allow for future copy-on-write optimizations, there is a distinction between writable and const access, the get() method is modified to return only a const pointer, with get_mutable() added to return a writable pointer. Furthermore, derefencing (operator*()) a mutable pointer will give a mutable reference (in so far as T is not declared const), and dereferencing a const pointer will give a const reference.
This class is entirely inline and has no computational or space overhead except when copying is required; it contains just a single pointer and does no reference counting.
Usage
In the simplest use case, the instantiation type will match the type of object it references, e.g.:
In this case, as longcopyable_unique_ptr<Foo> ptr = make_unique<Foo>(...);
Foo
is deemed compatible, the behavior will be as expected, i.e., whenptr
copies, it will contain a reference to a new instance ofFoo
.copyable_unique_ptr can also be used with polymorphic classes a copyable_unique_ptr, instantiated on a base class, references an instance of a derived class. When copying the object, we would want the copy to likewise contain an instance of the derived class. For example:
copyable_unique_ptr<Base> cu_ptr = make_unique<Derived>(); copyable_unique_ptr<Base> other_cu_ptr = cu_ptr; // Triggers a copy. is_dynamic_castable<Derived>(other_cu_ptr.get()); // Should be true.
This works for well-designed polymorphic classes.
The
Base
class’s Clone() implementation does not invoke theDerived
class’s implementation of a suitable virtual method.
- Warning
Ill-formed polymorphic classes can lead to fatal type slicing of the referenced object, such that the new copy contains an instance of
Base
instead ofDerived
. Some mistakes that would lead to this degenerate behavior:
- Template Parameters
T
: The type of the contained object, which must be copyable as defined above. May be an abstract or concrete type.
Constructors
-
copyable_unique_ptr
() noexcept¶ Default constructor stores a
nullptr
. No heap allocation is performed. The empty() method will return true when called on a default-constructed copyable_unique_ptr.
-
copyable_unique_ptr
(T *raw) noexcept¶ Given a raw pointer to a writable heap-allocated object, take over ownership of that object. No copying occurs.
-
copyable_unique_ptr
(const T &value)¶ Constructs a unique instance of T as a copy of the provided model value.
-
copyable_unique_ptr
(const copyable_unique_ptr &cu_ptr)¶ Copy constructor is deep; the new copyable_unique_ptr object contains a new copy of the object in the source, created via the source object’s copy constructor or
Clone()
method. If the source container is empty this one will be empty also.
-
template<typename
U
>copyable_unique_ptr
(const std::unique_ptr<U> &u_ptr)¶ Copy constructor from a standard
unique_ptr
of compatible type. The copy is deep; the new copyable_unique_ptr object contains a new copy of the object in the source, created via the source object’s copy constructor orClone()
method. If the source container is empty this one will be empty also.
-
copyable_unique_ptr
(copyable_unique_ptr &&cu_ptr) noexcept¶ Move constructor is very fast and leaves the source empty. Ownership is transferred from the source to the new copyable_unique_ptr. If the source was empty this one will be empty also. No heap activity occurs.
-
copyable_unique_ptr
(std::unique_ptr<T> &&u_ptr) noexcept¶ Move constructor from a standard
unique_ptr
. The move is very fast and leaves the source empty. Ownership is transferred from the source to the new copyable_unique_ptr. If the source was empty this one will be empty also. No heap activity occurs.
-
template<typename
U
>copyable_unique_ptr
(std::unique_ptr<U> &&u_ptr) noexcept¶ Move construction from a compatible standard
unique_ptr
. TypeU*
must be implicitly convertible to typeT*
. Ownership is transferred from the source to the new copyable_unique_ptr. If the source was empty this one will be empty also. No heap activity occurs.
Assignment
-
copyable_unique_ptr &
operator=
(T *raw) noexcept¶ This form of assignment replaces the currently-held object by the given source object and takes over ownership of the source object. The currently-held object (if any) is deleted.
-
copyable_unique_ptr &
operator=
(const T &ref)¶ This form of assignment replaces the currently-held object by a heap-allocated copy of the source object, created using its copy constructor or
Clone()
method. The currently-held object (if any) is deleted.
-
copyable_unique_ptr &
operator=
(const copyable_unique_ptr &cu_ptr)¶ Copy assignment from copyable_unique_ptr replaces the currently-held object by a copy of the object held in the source container, created using the source object’s copy constructor or
Clone()
method. The currently-held object (if any) is deleted. If the source container is empty this one will be empty also after the assignment. Nothing happens if the source and destination are the same container.
-
template<typename
U
>
copyable_unique_ptr &operator=
(const copyable_unique_ptr<U> &cu_ptr)¶ Copy assignment from a compatible copyable_unique_ptr replaces the currently-held object by a copy of the object held in the source container, created using the source object’s copy constructor or
Clone()
method. The currently-held object (if any) is deleted. If the source container is empty this one will be empty also after the assignment. Nothing happens if the source and destination are the same container.
-
copyable_unique_ptr &
operator=
(const std::unique_ptr<T> &src)¶ Copy assignment from a standard
unique_ptr
replaces the currently-held object by a copy of the object held in the source container, created using the source object’s copy constructor orClone()
method. The currently-held object (if any) is deleted. If the source container is empty this one will be empty also after the assignment. Nothing happens if the source and destination are the same container.
-
template<typename
U
>
copyable_unique_ptr &operator=
(const std::unique_ptr<U> &u_ptr)¶ Copy assignment from a compatible standard
unique_ptr
replaces the currently-held object by a copy of the object held in the source container, created using the source object’s copy constructor orClone()
method. The currently-held object (if any) is deleted. If the source container is empty this one will be empty also after the assignment. Nothing happens if the source and destination are the same container.
-
copyable_unique_ptr &
operator=
(copyable_unique_ptr &&cu_ptr) noexcept¶ Move assignment replaces the currently-held object by the source object, leaving the source empty. The currently-held object (if any) is deleted. The instance is not copied. Nothing happens if the source and destination are the same containers.
-
template<typename
U
>
copyable_unique_ptr &operator=
(copyable_unique_ptr<U> &&cu_ptr) noexcept¶ Move assignment replaces the currently-held object by the compatible source object, leaving the source empty. The currently-held object (if any) is deleted. The instance is not copied. Nothing happens if the source and destination are the same containers.
-
copyable_unique_ptr &
operator=
(std::unique_ptr<T> &&u_ptr) noexcept¶ Move assignment replaces the currently-held object by the source object, leaving the source empty. The currently-held object (if any) is deleted. The instance is not copied. Nothing happens if the source and destination are the same containers.
-
template<typename
U
>
copyable_unique_ptr &operator=
(std::unique_ptr<U> &&u_ptr) noexcept¶ Move assignment replaces the currently-held object by the compatible source object, leaving the source empty. The currently-held object (if any) is deleted. The instance is not copied. Nothing happens if the source and destination are the same containers.
Observers
-
bool
empty
() const noexcept¶ Return true if this container is empty, which is the state the container is in immediately after default construction and various other operations.
-
const T *
get
() const noexcept¶ Return a const pointer to the contained object if any, or
nullptr
. Note that this is different thanget()
for the standard smart pointers likestd::unique_ptr
which return a writable pointer. Use get_mutable() here for that purpose.
-
T *
get_mutable
() noexcept¶ Return a writable pointer to the contained object if any, or
nullptr
. Note that you need write access to this container in order to get write access to the object it contains.- Warning
If copyable_unique_ptr is instantiated on a const template parameter (e.g.,
copyable_unique_ptr<const Foo>
), then get_mutable() returns a const pointer.
-
const T &
operator*
() const¶ Return a const reference to the contained object. Note that this is different from
std::unique_ptr::operator*()
which would return a non-const reference (ifT
is non-const), even if the container itself is const. For a const copyable_unique_ptr will always return a const reference to its contained value.- Warning
Currently copyable_unique_ptr is a std::unique_ptr. As such, a const copyable_unique_ptr<Foo> can be upcast to a const unique_ptr<Foo> and the parent’s behavior will provide a mutable reference. This is strongly discouraged and will break as the implementation of this class changes to shore up this gap in the const correctness protection.
- Pre
this != nullptr
reportstrue
.
-
T &
operator*
()¶ Return a writable reference to the contained object (if T is itself not const). Note that you need write access to this container in order to get write access to the object it contains.
We strongly recommend, that, if dereferencing a copyable_unique_ptr without the intention of mutating the underlying value, prefer to dereference a const copyable_unique_ptr (or use *my_ptr.get()) and not a mutable copyable_unique_ptr. As “copy-on-write” behavior is introduced in the future, this recommended practice will prevent unwanted copies of the underlying value.
If copyable_unique_ptr is instantiated on a const template parameter (e.g.,
copyable_unique_ptr<const Foo>
), then operator*() must return a const reference.- Pre
this != nullptr
reportstrue
.
Related
-
template<class
charT
, classtraits
, classT
>
std::basic_ostream<charT, traits> &operator<<
(std::basic_ostream<charT, traits> &os, const copyable_unique_ptr<T> &cu_ptr)¶ Output the system-dependent representation of the pointer contained in a copyable_unique_ptr object. This is equivalent to
os << p.get();
.
-
struct
CpuUsage
¶ - #include <CpuUsage.hpp>
CpuUsage structure
Average usage in percent and time span of the average (since last query)
-
struct
CrashDump
¶
-
class
DataInputQueue
¶ - #include <DataQueue.hpp>
Access to send messages through XLink stream
Public Functions
-
bool
isClosed
() const¶ Check whether queue is closed
- Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.
-
void
close
()¶ Closes the queue and the underlying thread
-
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
() const¶ Gets queue maximum size
- Return
Maximum queue size
-
std::string
getName
() const¶ Gets queues name
- Return
Queue name
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
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
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 queuetimeout
: Maximum duration to block in milliseconds
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 queuetimeout
: 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 queuetimeout
: Maximum duration to block in milliseconds
-
bool
-
class
DataOutputQueue
¶ - #include <DataQueue.hpp>
Access to receive messages coming from XLink stream
Public Types
-
using
CallbackId
= int¶ Alias for callback id.
Public Functions
-
bool
isClosed
() const¶ Check whether queue is closed
- Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.
-
void
close
()¶ Closes the queue and the underlying thread
-
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
() const¶ Gets queue maximum size
- Return
Maximum queue size
-
std::string
getName
() const¶ Gets queues name
- Return
Queue name
Adds a callback on message received
- Return
Callback id
- Parameters
callback
: Callback function with queue name and message pointer
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
>
boolhas
()¶ 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
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 immediately with nullptr
- Return
Message or nullptr if no message available
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
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
Block until a message is available with a timeout.
- Return
Message of type T otherwise nullptr if message isn’t type T or timeout occurred
- Parameters
timeout
: Duration for which the function should block[out] hasTimedout
: Outputs true if timeout occurred, false otherwise
Block until a message is available with a timeout.
- Return
Message of type T otherwise nullptr if message isn’t type T or timeout occurred
- Parameters
timeout
: Duration for which the function should block[out] hasTimedout
: Outputs true if timeout occurred, false otherwise
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
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
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 occurred, false otherwise
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 occurred, false otherwise
-
using
-
struct
DetectionNetworkProperties
: public dai::PropertiesSerializable<NeuralNetworkProperties, DetectionNetworkProperties>¶ - #include <DetectionNetworkProperties.hpp>
Specify properties for DetectionNetwork
Subclassed by dai::PropertiesSerializable< DetectionNetworkProperties, SpatialDetectionNetworkProperties >
-
struct
DetectionParserOptions
¶ - #include <DetectionParserOptions.hpp>
Specifies how to parse output of detection networks
-
struct
DetectionParserProperties
: public dai::PropertiesSerializable<Properties, DetectionParserProperties>¶ - #include <DetectionParserProperties.hpp>
Specify properties for DetectionParser
Public Members
-
int
numFramesPool
= 8¶ Num frames in output pool.
-
std::unordered_map<std::string, TensorInfo>
networkInputs
¶ Network inputs.
-
DetectionParserOptions
parser
¶ Options for parser.
-
int
-
class
Device
: public dai::DeviceBase - #include <Device.hpp>
Represents the DepthAI device with the methods to interact with it. Implements the host-side queues to connect with XLinkIn and XLinkOut nodes
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
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>Device
(const Pipeline &pipeline, T usb2Mode) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the deviceusb2Mode
: (bool) Boot device using USB2 mode firmware
-
Device
(const Pipeline &pipeline, UsbSpeed maxUsbSpeed) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the devicemaxUsbSpeed
: Maximum allowed USB speed
-
Device
(const Pipeline &pipeline, const dai::Path &pathToCmd) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
Device
(const Pipeline &pipeline, const DeviceInfo &devInfo) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>Device
(const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: (bool) Boot device using USB2 mode firmware
-
Device
(const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
Device
(const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmware
-
Device
() Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
-
~Device
() override dtor to close the device
-
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 nodemaxSize
: Maximum number of messages in queueblocking
: 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 XLinkIn nodemaxSize
: Maximum number of messages in queueblocking
: 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 blockmaxNumEvents
: Maximum number of events to remove from queue - Default is unlimitedtimeout
: 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 formaxNumEvents
: Maximum number of events to remove from queue. Default is unlimitedtimeout
: 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 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 unlimitedtimeout
: 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 fortimeout
: 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 fortimeout
: 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
-
DeviceBase
(const Pipeline &pipeline) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the device
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(const Pipeline &pipeline, T usb2Mode) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the deviceusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(const Pipeline &pipeline, UsbSpeed maxUsbSpeed) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the devicemaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(const Pipeline &pipeline, const dai::Path &pathToCmd) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd) Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmware
-
DeviceBase
() Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
-
DeviceBase
(OpenVINO::Version version) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
version
: OpenVINO version which the device will be booted with.
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(OpenVINO::Version version, T usb2Mode) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
version
: OpenVINO version which the device will be booted withusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(OpenVINO::Version version, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withmaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(OpenVINO::Version version, const dai::Path &pathToCmd) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo) Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, T usb2Mode) Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, const dai::Path &pathToCmd) Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmware
-
DeviceBase
(Config config) Connects to any available device with custom config.
- Parameters
config
: Device custom configuration to boot with
-
DeviceBase
(Config config, const DeviceInfo &devInfo) Connects to device ‘devInfo’ with custom config.
- Parameters
config
: Device custom configuration to boot withdevInfo
: DeviceInfo which specifies which device to connect to
-
DeviceBase
(const DeviceInfo &devInfo) Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
devInfo
: DeviceInfo which specifies which device to connect to
-
DeviceBase
(const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed) Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
devInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(std::string nameOrDeviceId) Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
nameOrDeviceId
: Creates DeviceInfo with nameOrDeviceId to connect to
-
DeviceBase
(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed) Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
nameOrDeviceId
: Creates DeviceInfo with nameOrDeviceId to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(Config config, T usb2Mode) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
config
: Config with which the device will be booted withusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(Config config, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withmaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(Config config, const dai::Path &pathToCmd) Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
config
: Config with which the device will be booted withpathToCmd
: Path to custom device firmware
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(Config config, const DeviceInfo &devInfo, T usb2Mode) Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed) Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(Config config, const DeviceInfo &devInfo, const dai::Path &pathToCmd, bool dumpOnly = false) Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmwaredumpOnly
: If true only the minimal connection is established to retrieve the crash dump
Public Static Attributes
-
constexpr std::size_t
EVENT_QUEUE_MAXIMUM_SIZE
= {2048} Maximum number of elements in event queue.
-
-
class
DeviceBase
¶ - #include <DeviceBase.hpp>
The core of depthai device for RAII, connects to device and maintains watchdog, timesync, …
Subclassed by dai::Device
Public Functions
-
DeviceBase
(const Pipeline &pipeline)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the device
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(const Pipeline &pipeline, T usb2Mode)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the deviceusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(const Pipeline &pipeline, UsbSpeed maxUsbSpeed)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
pipeline
: Pipeline to be executed on the devicemaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(const Pipeline &pipeline, const dai::Path &pathToCmd)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo)¶ Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode)¶ Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)¶ Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd)¶ Connects to device specified by devInfo.
- Parameters
pipeline
: Pipeline to be executed on the devicedevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmware
-
DeviceBase
()¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
-
DeviceBase
(OpenVINO::Version version)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
version
: OpenVINO version which the device will be booted with.
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(OpenVINO::Version version, T usb2Mode)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
version
: OpenVINO version which the device will be booted withusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(OpenVINO::Version version, UsbSpeed maxUsbSpeed)¶ Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withmaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(OpenVINO::Version version, const dai::Path &pathToCmd)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo)¶ Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, T usb2Mode)¶ Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)¶ Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(OpenVINO::Version version, const DeviceInfo &devInfo, const dai::Path &pathToCmd)¶ Connects to device specified by devInfo.
- Parameters
version
: OpenVINO version which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmware
-
DeviceBase
(Config config)¶ Connects to any available device with custom config.
- Parameters
config
: Device custom configuration to boot with
-
DeviceBase
(Config config, const DeviceInfo &devInfo)¶ Connects to device ‘devInfo’ with custom config.
- Parameters
config
: Device custom configuration to boot withdevInfo
: DeviceInfo which specifies which device to connect to
-
DeviceBase
(const DeviceInfo &devInfo)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
devInfo
: DeviceInfo which specifies which device to connect to
-
DeviceBase
(const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
devInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(std::string nameOrDeviceId)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
nameOrDeviceId
: Creates DeviceInfo with nameOrDeviceId to connect to
-
DeviceBase
(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters
nameOrDeviceId
: Creates DeviceInfo with nameOrDeviceId to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(Config config, T usb2Mode)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters
config
: Config with which the device will be booted withusb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(Config config, UsbSpeed maxUsbSpeed)¶ Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withmaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(Config config, const dai::Path &pathToCmd)¶ Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBase
(Config config, const DeviceInfo &devInfo, T usb2Mode)¶ Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tousb2Mode
: Boot device using USB2 mode firmware
-
DeviceBase
(Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)¶ Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect tomaxUsbSpeed
: Maximum allowed USB speed
-
DeviceBase
(Config config, const DeviceInfo &devInfo, const dai::Path &pathToCmd, bool dumpOnly = false)¶ Connects to device specified by devInfo.
- Parameters
config
: Config with which the device will be booted withdevInfo
: DeviceInfo which specifies which device to connect topathToCmd
: Path to custom device firmwaredumpOnly
: If true only the minimal connection is established to retrieve the crash dump
-
~DeviceBase
()¶ Device destructor
- Note
In the destructor of the derived class, remember to call close()
-
tl::optional<Version>
getBootloaderVersion
()¶ Gets Bootloader version if it was booted through Bootloader
- Return
DeviceBootloader::Version if booted through Bootloader or none otherwise
-
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 transferred from device to host.
- Parameters
level
: Logging severity
-
LogLevel
getLogLevel
()¶ Gets current logging severity level of the device.
- Return
Logging severity level
-
void
setXLinkChunkSize
(int sizeBytes)¶ Sets the chunk size for splitting device-sent XLink packets. A larger value could increase performance, and 0 disables chunking. A negative value is ignored. Device defaults are configured per protocol, currently 64*1024 for both USB and Ethernet.
- Parameters
sizeBytes
: XLink chunk size in bytes
-
int
getXLinkChunkSize
()¶ Gets current XLink chunk size.
- Return
XLink chunk size in bytes
-
void
setXLinkRateLimit
(int maxRateBytesPerSecond, int burstSize = 0, int waitUs = 0)¶ Sets the maximum transmission rate for the XLink connection on device side, using a simple token bucket algorithm. Useful for bandwidth throttling
- Parameters
maxRateBytesPerSecond
: Rate limit in Bytes/secondburstSize
: Size in Bytes for how much to attempt to send once, 0 = autowaitUs
: Time in microseconds to wait for replenishing tokens, 0 = auto
-
DeviceInfo
getDeviceInfo
() const¶ Get the Device Info object o the device which is currently running
- Return
DeviceInfo of the current device in execution
-
std::string
getDeviceName
()¶ Get device name if available
- Return
device name or empty string if not available
-
std::string
getProductName
()¶ Get product name if available
- Return
product name or empty string if not available
-
std::string
getMxId
()¶ Get MxId of device
- Return
MxId of connected device
-
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
-
bool
setIrLaserDotProjectorBrightness
(float mA, int mask = -1)¶ Sets the brightness of the IR Laser Dot Projector. Limits: up to 765mA at 30% duty cycle, up to 1200mA at 6% duty cycle. The duty cycle is controlled by
left
camera STROBE, aligned to start of exposure. The emitter is turned off by default- Return
True on success, false if not found or other failure
- Parameters
mA
: Current in mA that will determine brightness, 0 or negative to turn offmask
: Optional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
-
bool
setIrFloodLightBrightness
(float mA, int mask = -1)¶ Sets the brightness of the IR Flood Light. Limits: up to 1500mA at 30% duty cycle. The duty cycle is controlled by the
left
camera STROBE, aligned to start of exposure. If the dot projector is also enabled, its lower duty cycle limits take precedence. The emitter is turned off by default- Return
True on success, false if not found or other failure
- Parameters
mA
: Current in mA that will determine brightness, 0 or negative to turn offmask
: Optional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
-
bool
setIrLaserDotProjectorIntensity
(float intensity, int mask = -1)¶ Sets the intensity of the IR Laser Dot Projector. Limits: up to 765mA at 30% frame time duty cycle when exposure time is longer than 30% frame time. Otherwise, duty cycle is 100% of exposure time, with current increased up to max 1200mA to make up for shorter duty cycle. The duty cycle is controlled by
left
camera STROBE, aligned to start of exposure. The emitter is turned off by default- Return
True on success, false if not found or other failure
- Parameters
intensity
: Intensity on range 0 to 1, that will determine brightness. 0 or negative to turn offmask
: Optional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
-
bool
setIrFloodLightIntensity
(float intensity, int mask = -1)¶ Sets the intensity of the IR Flood Light. Limits: Intensity is directly normalized to 0 - 1500mA current. The duty cycle is 30% when exposure time is longer than 30% frame time. Otherwise, duty cycle is 100% of exposure time. The duty cycle is controlled by the
left
camera STROBE, aligned to start of exposure. The emitter is turned off by default- Return
True on success, false if not found or other failure
- Parameters
intensity
: Intensity on range 0 to 1, that will determine brightness, 0 or negative to turn offmask
: Optional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
-
std::vector<std::tuple<std::string, int, int>>
getIrDrivers
()¶ Retrieves detected IR laser/LED drivers.
- Return
Vector of tuples containing: driver name, I2C bus, I2C address. For OAK-D-Pro it should be
[{"LM3644", 2, 0x63}]
-
bool
hasCrashDump
()¶ Retrieves whether the is crash dump stored on device or not.
-
ProfilingData
getProfilingData
()¶ Get current accumulated profiling data
- Return
ProfilingData from the specific device
-
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::vector<CameraBoardSocket>
getConnectedCameras
()¶ Get cameras that are connected to the device
- Return
Vector of connected cameras
-
std::vector<ConnectionInterface>
getConnectionInterfaces
()¶ Get connection interfaces for device
- Return
Vector of connection type
-
std::vector<CameraFeatures>
getConnectedCameraFeatures
()¶ Get cameras that are connected to the device with their features/properties
- Return
Vector of connected camera features
-
std::vector<StereoPair>
getStereoPairs
()¶ Get stereo pairs based on the device type.
- Return
Vector of stereo pairs
-
std::vector<StereoPair>
getAvailableStereoPairs
()¶ Get stereo pairs taking into account the calibration and connected cameras.
- Note
This method will always return a subset of
getStereoPairs
.- Return
Vector of stereo pairs
-
std::unordered_map<CameraBoardSocket, std::string>
getCameraSensorNames
()¶ Get sensor names for cameras that are connected to the device
- Return
Map/dictionary with camera sensor names, indexed by socket
-
std::string
getConnectedIMU
()¶ Get connected IMU type
- Return
IMU type
-
dai::Version
getEmbeddedIMUFirmwareVersion
()¶ Get embedded IMU firmware version to which IMU can be upgraded
- Return
Get embedded IMU firmware version to which IMU can be upgraded.
-
bool
startIMUFirmwareUpdate
(bool forceUpdate = false)¶ Starts IMU firmware update asynchronously only if IMU node is not running. If current firmware version is the same as embedded firmware version then it’s no-op. Can be overridden by forceUpdate parameter. State of firmware update can be monitored using getIMUFirmwareUpdateStatus API.
- Return
Returns whether firmware update can be started. Returns false if IMU node is started.
- Parameters
forceUpdate
: Force firmware update or not. Will perform FW update regardless of current version and embedded firmware version.
-
std::tuple<bool, unsigned int>
getIMUFirmwareUpdateStatus
()¶ Get IMU firmware update status
- Return
Whether IMU firmware update is done and last firmware update progress as percentage. return value true and 100 means that the update was successful return value true and other than 100 means that the update failed
-
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
-
bool
isEepromAvailable
()¶ Check if EEPROM is available
- Return
True if EEPROM is present on board, false otherwise
-
bool
flashCalibration
(CalibrationHandler calibrationDataHandler)¶ Stores the Calibration and Device information to the Device EEPROM
- Return
true on successful flash, false on failure
- Parameters
calibrationObj
: CalibrationHandler object which is loaded with calibration information.
-
void
flashCalibration2
(CalibrationHandler calibrationDataHandler)¶ Stores the Calibration and Device information to the Device EEPROM
- Exceptions
std::runtime_exception
: if failed to flash the calibration
- Parameters
calibrationObj
: CalibrationHandler object which is loaded with calibration information.
-
CalibrationHandler
readCalibration
()¶ Fetches the EEPROM data from the device and loads it into CalibrationHandler object If no calibration is flashed, it returns default
- Return
The CalibrationHandler object containing the calibration currently flashed on device EEPROM
-
CalibrationHandler
readCalibration2
()¶ Fetches the EEPROM data from the device and loads it into CalibrationHandler object
- Return
The CalibrationHandler object containing the calibration currently flashed on device EEPROM
- Exceptions
std::runtime_exception
: if no calibration is flashed
-
CalibrationHandler
readCalibrationOrDefault
()¶ Fetches the EEPROM data from the device and loads it into CalibrationHandler object If no calibration is flashed, it returns default
- Return
The CalibrationHandler object containing the calibration currently flashed on device EEPROM
-
void
factoryResetCalibration
()¶ Factory reset EEPROM data if factory backup is available.
- Exceptions
std::runtime_exception
: If factory reset was unsuccessful
-
void
flashFactoryCalibration
(CalibrationHandler calibrationHandler)¶ Stores the Calibration and Device information to the Device EEPROM in Factory area To perform this action, correct env variable must be set
- Return
True on successful flash, false on failure
- Exceptions
std::runtime_exception
: if failed to flash the calibration
-
void
flashEepromClear
()¶ Destructive action, deletes User area EEPROM contents Requires PROTECTED permissions
- Return
True on successful flash, false on failure
- Exceptions
std::runtime_exception
: if failed to flash the calibration
-
void
flashFactoryEepromClear
()¶ Destructive action, deletes Factory area EEPROM contents Requires FACTORY PROTECTED permissions
- Return
True on successful flash, false on failure
- Exceptions
std::runtime_exception
: if failed to flash the calibration
-
CalibrationHandler
readFactoryCalibration
()¶ Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object
- Return
The CalibrationHandler object containing the calibration currently flashed on device EEPROM in Factory Area
- Exceptions
std::runtime_exception
: if no calibration is flashed
-
CalibrationHandler
readFactoryCalibrationOrDefault
()¶ Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object If no calibration is flashed, it returns default
- Return
The CalibrationHandler object containing the calibration currently flashed on device EEPROM in Factory Area
-
std::vector<std::uint8_t>
readCalibrationRaw
()¶ Fetches the raw EEPROM data from User area
- Return
Binary dump of User area EEPROM data
- Exceptions
std::runtime_exception
: if any error occurred
-
std::vector<std::uint8_t>
readFactoryCalibrationRaw
()¶ Fetches the raw EEPROM data from Factory area
- Return
Binary dump of Factory area EEPROM data
- Exceptions
std::runtime_exception
: if any error occurred
-
UsbSpeed
getUsbSpeed
()¶ Retrieves USB connection speed
- Return
USB connection speed of connected device if applicable. Unknown otherwise.
-
void
setTimesync
(std::chrono::milliseconds period, int numSamples, bool random)¶ Configures Timesync service on device. It keeps host and device clocks in sync First time timesync is started it waits until the initial sync is completed Afterwards the function changes the following parameters
- Parameters
period
: Interval between timesync runsnumSamples
: Number of timesync samples per run which are used to compute a better value. Set to zero to disable timesyncrandom
: If true partial timesync requests will be performed at random intervals, otherwise at fixed intervals
-
void
setTimesync
(bool enable)¶ Enables or disables Timesync service on device. It keeps host and device clocks in sync.
- Parameters
enable
: Enables or disables consistent timesyncing
-
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)
- Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.
-
std::shared_ptr<XLinkConnection>
getConnection
()¶ Returns underlying XLinkConnection
-
std::shared_ptr<const XLinkConnection>
getConnection
() const¶ Returns underlying XLinkConnection
Public Static Functions
-
std::chrono::milliseconds
getDefaultSearchTime
()¶ Get the Default Search Time for finding devices.
- Return
Default search time in milliseconds
-
std::tuple<bool, DeviceInfo>
getAnyAvailableDevice
(std::chrono::milliseconds 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>
getAnyAvailableDevice
(std::chrono::milliseconds timeout, std::function<void()> cb)¶ 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 devicecb
: callback function called between pooling intervals
-
std::tuple<bool, DeviceInfo>
getFirstAvailableDevice
(bool skipInvalidDevice = true)¶ 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 available devices
- Return
Vector of available devices
-
std::vector<DeviceInfo>
getAllConnectedDevices
()¶ Returns information of all connected devices. The devices could be both connectable as well as already connected to devices.
- Return
Vector of connected device information
-
std::vector<std::uint8_t>
getEmbeddedDeviceBinary
(bool usb2Mode, OpenVINO::Version version = OpenVINO::VERSION_UNIVERSAL)¶ Gets device firmware binary for a specific OpenVINO version
-
std::vector<std::uint8_t>
getEmbeddedDeviceBinary
(Config config)¶ Gets device firmware binary for a specific configuration
- Return
Firmware binary
- Parameters
config
: FW with applied configuration
-
ProfilingData
getGlobalProfilingData
()¶ Get current global accumulated profiling data
- Return
ProfilingData from all devices
Public Static Attributes
-
constexpr std::chrono::seconds
DEFAULT_SEARCH_TIME
= {3}¶ Default search time for constructors which discover devices.
-
constexpr float
DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ
= {1.0f}¶ Default rate at which system information is logged.
-
constexpr std::chrono::milliseconds
DEFAULT_TIMESYNC_PERIOD
= {5000}¶ Default Timesync period.
-
constexpr int
DEFAULT_TIMESYNC_NUM_SAMPLES
= {10}¶ Default Timesync number of samples per sync.
-
constexpr bool
DEFAULT_TIMESYNC_RANDOM
= {true}¶ Default Timesync packet interval randomness.
-
-
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; flashing not allowed
- Parameters
devInfo
: DeviceInfo of which to boot or connect to
-
template<typename
T
, std::enable_if_t<std::is_same<T, bool>::value, bool> = true>DeviceBootloader
(const DeviceInfo &devInfo, T allowFlashingBootloader)¶ Connects to or boots device in bootloader mode depending on devInfo state.
- Parameters
devInfo
: DeviceInfo of which to boot or connect toallowFlashingBootloader
: (bool) Set to true to allow flashing the devices bootloader
-
DeviceBootloader
(const DeviceInfo &devInfo, Type type, bool allowFlashingBootloader = false)¶ Connects to device in bootloader of specified type. Throws if it wasn’t possible. This constructor will automatically boot into specified bootloader type if not already running
- Parameters
devInfo
: DeviceInfo of which to boot or connect totype
: Type of bootloader to boot/connect to.allowFlashingBootloader
: Set to true to allow flashing the devices bootloader. Defaults to false
-
DeviceBootloader
(const DeviceInfo &devInfo, const dai::Path &pathToBootloader, bool allowFlashingBootloader = false)¶ 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 topathToBootloader
: Custom bootloader firmware to bootallowFlashingBootloader
: Set to true to allow flashing the devices bootloader. Defaults to false
-
DeviceBootloader
(std::string nameOrDeviceId, bool allowFlashingBootloader = false)¶ Connects to device with specified name/device id
- Parameters
nameOrDeviceId
: Creates DeviceInfo with nameOrDeviceId to connect toallowFlashingBootloader
: Set to true to allow flashing the devices bootloader. Defaults to false
-
std::tuple<bool, std::string>
flash
(std::function<void(float)> progressCallback, const Pipeline &pipeline, bool compress = false, std::string applicationName = "", Memory memory = Memory::AUTO, bool checkChecksum = false, )¶ Flashes a given pipeline to the device.
- Parameters
progressCallback
: Callback that sends back a value between 0..1 which signifies current flashing progresspipeline
: Pipeline to flash to the boardcompress
: Compresses application to reduce needed memory sizeapplicationName
: Name the application that is flashed
-
std::tuple<bool, std::string>
flash
(const Pipeline &pipeline, bool compress = false, std::string applicationName = "", Memory memory = Memory::AUTO, bool checkChecksum = false)¶ Flashes a given pipeline to the device.
- Parameters
pipeline
: Pipeline to flash to the boardcompress
: Compresses application to reduce needed memory sizeapplicationName
: Optional name the application that is flashed
-
ApplicationInfo
readApplicationInfo
(Memory memory)¶ Reads information about flashed application in specified memory from device
- Parameters
memory
: Specifies which memory to query
-
std::tuple<bool, std::string>
flashDepthaiApplicationPackage
(std::function<void(float)> progressCallback, std::vector<uint8_t> package, Memory memory = Memory::AUTO, )¶ 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 progresspackage
: Depthai application package to flash to the board
-
std::tuple<bool, std::string>
flashDepthaiApplicationPackage
(std::vector<uint8_t> package, Memory memory = Memory::AUTO)¶ Flashes a specific depthai application package that was generated using createDepthaiApplicationPackage or saveDepthaiApplicationPackage
- Parameters
package
: Depthai application package to flash to the board
-
std::tuple<bool, std::string>
flashClear
(Memory memory = Memory::AUTO)¶ Clears flashed application on the device, by removing SBR boot structure Doesn’t remove fast boot header capability to still boot the application
-
std::tuple<bool, std::string>
flashBootloader
(std::function<void(float)> progressCallback, const dai::Path &path = {}, )¶ Flashes bootloader to the current board
- Parameters
progressCallback
: Callback that sends back a value between 0..1 which signifies current flashing progresspath
: Optional parameter to custom bootloader to flash
-
std::tuple<bool, std::string>
flashBootloader
(Memory memory, Type type, std::function<void(float)> progressCallback, const dai::Path &path = {}, )¶ Flash selected bootloader to the current board
- Parameters
memory
: Memory to flashtype
: Bootloader type to flashprogressCallback
: Callback that sends back a value between 0..1 which signifies current flashing progresspath
: Optional parameter to custom bootloader to flash
-
std::tuple<bool, std::string>
flashUserBootloader
(std::function<void(float)> progressCallback, const dai::Path &path = {}, )¶ Flashes user bootloader to the current board. Available for NETWORK bootloader type
- Parameters
progressCallback
: Callback that sends back a value between 0..1 which signifies current flashing progresspath
: Optional parameter to custom bootloader to flash
-
std::tuple<bool, std::string>
flashGpioModeBootHeader
(Memory memory, int gpioMode)¶ Flash boot header which boots same as equivalent GPIO mode would
- Parameters
gpioMode
: GPIO mode equivalent
-
std::tuple<bool, std::string>
flashUsbRecoveryBootHeader
(Memory memory)¶ Flash USB recovery boot header. Switches to USB ROM Bootloader
- Parameters
memory
: Which memory to flash the header to
-
std::tuple<bool, std::string>
flashBootHeader
(Memory memory, int32_t frequency = -1, int64_t location = -1, int32_t dummyCycles = -1, int64_t offset = -1)¶ Flash optimized boot header
- Return
status as std::tuple<bool, std::string>
- Parameters
memory
: Which memory to flasht the header tofrequency
: SPI specific parameter, frequency in MHzlocation
: Target location the header should boot to. Default to location of bootloaderdummyCycles
: SPI specific parameteroffset
: Offset in memory to flash the header to. Defaults to offset of boot header
-
std::tuple<bool, std::string>
flashFastBootHeader
(Memory memory, int32_t frequency = -1, int64_t location = -1, int32_t dummyCycles = -1, int64_t offset = -1)¶ Flash fast boot header. Application must already be present in flash, or location must be specified manually. Note - Can soft brick your device if firmware location changes.
- Return
status as std::tuple<bool, std::string>
- Parameters
memory
: Which memory to flash the header tofrequency
: SPI specific parameter, frequency in MHzlocation
: Target location the header should boot to. Default to location of bootloaderdummyCycles
: SPI specific parameteroffset
: Offset in memory to flash the header to. Defaults to offset of boot header
-
std::tuple<bool, std::string>
flashCustom
(Memory memory, size_t offset, const std::vector<uint8_t> &data, std::function<void(float)> progressCb = nullptr)¶ Flash arbitrary data at custom offset in specified memory
- Parameters
memory
: Memory to flashoffset
: Offset at which to flash the given data in bytesprogressCallback
: Callback that sends back a value between 0..1 which signifies current flashing progressdata
: Data to flash
-
std::tuple<bool, std::string>
readCustom
(Memory memory, size_t offset, size_t size, std::vector<uint8_t> &data, std::function<void(float)> progressCb = nullptr)¶ Reads arbitrary data at custom offset in specified memory
- Parameters
memory
: Memory to readoffset
: Offset at which to read the specified bytessize
: Number of bytes to readdata
: Data to read to. Must be at least ‘size’ number of bytes bigprogressCallback
: Callback that sends back a value between 0..1 which signifies current reading progress
-
nlohmann::json
readConfigData
(Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Reads configuration data from bootloader
- Return
Unstructured configuration data
- Parameters
memory
: Optional - from which memory to read configuration datatype
: Optional - from which type of bootloader to read configuration data
-
std::tuple<bool, std::string>
flashConfigData
(nlohmann::json configData, Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Flashes configuration data to bootloader
- Parameters
configData
: Unstructured configuration datamemory
: Optional - to which memory flash configurationtype
: Optional - for which type of bootloader to flash configuration
-
std::tuple<bool, std::string>
flashConfigFile
(const dai::Path &configPath, Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Flashes configuration data to bootloader
- Parameters
configPath
: Unstructured configuration datamemory
: Optional - to which memory flash configurationtype
: Optional - for which type of bootloader to flash configuration
-
std::tuple<bool, std::string>
flashConfigClear
(Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Clears configuration data
- Parameters
memory
: Optional - on which memory to clear configuration datatype
: Optional - for which type of bootloader to clear configuration data
-
Config
readConfig
(Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Reads configuration from bootloader
- Return
Configuration structure
- Parameters
memory
: Optional - from which memory to read configurationtype
: Optional - from which type of bootloader to read configuration
-
std::tuple<bool, std::string>
flashConfig
(const Config &config, Memory memory = Memory::AUTO, Type type = Type::AUTO)¶ Flashes configuration to bootloader
- Parameters
configData
: Configuration structurememory
: Optional - to which memory flash configurationtype
: Optional - for which type of bootloader to flash configuration
-
MemoryInfo
getMemoryInfo
(Memory memory)¶ Retrieves information about specified memory
- Parameters
memory
: Specifies which memory to query
-
bool
isUserBootloaderSupported
()¶ Checks whether User Bootloader is supported with current bootloader
- Return
true of User Bootloader is supported, false otherwise
-
bool
isUserBootloader
()¶ Retrieves whether current bootloader is User Bootloader (B out of A/B configuration)
-
void
bootMemory
(const std::vector<uint8_t> &fw)¶ Boots a custom FW in memory
- Parameters
fw
:
- Exceptions
A
: runtime exception if there are any communication issues
-
void
bootUsbRomBootloader
()¶ Boots into integrated ROM bootloader in USB mode
- Exceptions
A
: runtime exception if there are any communication issues
-
tl::optional<Version>
getFlashedVersion
() const¶ - Return
Version of the bootloader that is flashed on the device. Nullopt when the version could not be retrieved because the device was in X_LINK_UNBOOTED state before booting the bootloader.
-
bool
isEmbeddedVersion
() const¶ - Return
True when bootloader was booted using latest bootloader integrated in the library. False when bootloader is already running on the device and just connected to.
-
Type
getType
() const¶ - Return
Type of currently connected bootloader
-
bool
isAllowedFlashingBootloader
() const¶ - Return
True if allowed to flash bootloader
-
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)
- Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.
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
(const Pipeline &pipeline, const dai::Path &pathToCmd = {}, bool compress = false, std::string applicationName = "", bool checkChecksum = false)¶ Creates application package which can be flashed to depthai device.
- Return
Depthai application package
- Parameters
pipeline
: Pipeline from which to create the application packagepathToCmd
: Optional path to custom device firmwarecompress
: Optional boolean which specifies if contents should be compressedapplicationName
: Optional name the application that is flashed
-
std::vector<uint8_t>
createDepthaiApplicationPackage
(const Pipeline &pipeline, bool compress, std::string applicationName = "", bool checkChecksum = false)¶ Creates application package which can be flashed to depthai device.
- Return
Depthai application package
- Parameters
pipeline
: Pipeline from which to create the application packagecompress
: Specifies if contents should be compressedapplicationName
: Name the application that is flashed
-
void
saveDepthaiApplicationPackage
(const dai::Path &path, const Pipeline &pipeline, const dai::Path &pathToCmd = {}, bool compress = false, std::string applicationName = "", bool checkChecksum = false)¶ Saves application package to a file which can be flashed to depthai device.
- Parameters
path
: Path where to save the application packagepipeline
: Pipeline from which to create the application packagepathToCmd
: Optional path to custom device firmwarecompress
: Optional boolean which specifies if contents should be compressedapplicationName
: Optional name the application that is flashed
-
void
saveDepthaiApplicationPackage
(const dai::Path &path, const Pipeline &pipeline, bool compress, std::string applicationName = "", bool checkChecksum = false)¶ Saves application package to a file which can be flashed to depthai device.
-
std::vector<std::uint8_t>
getEmbeddedBootloaderBinary
(Type type = DEFAULT_TYPE)¶ - Return
Embedded bootloader binary
Public Static Attributes
-
constexpr const Type
DEFAULT_TYPE
= {Type::USB}¶ Default Bootloader type.
-
struct
ApplicationInfo
¶
-
struct
Config
: public dai::bootloader::Config¶ Public Functions
-
void
setStaticIPv4
(std::string ip, std::string mask, std::string gateway)¶ Setting a static IPv4 won’t start DHCP client.
-
void
setDynamicIPv4
(std::string ip, std::string mask, std::string gateway)¶ Setting a dynamic IPv4 will set that IP as well as start DHCP client.
-
bool
isStaticIPV4
()¶ Get if static IPv4 configuration is set.
-
std::string
getIPv4
()¶ Get IPv4.
-
std::string
getIPv4Mask
()¶ Get IPv4 mask.
-
std::string
getIPv4Gateway
()¶ Get IPv4 gateway.
-
void
setDnsIPv4
(std::string dns, std::string dnsAlt = "")¶ Set IPv4 DNS options.
-
std::string
getDnsIPv4
()¶ Get primary IPv4 DNS server.
-
std::string
getDnsAltIPv4
()¶ Get alternate IPv4 DNS server.
-
void
setUsbTimeout
(std::chrono::milliseconds ms)¶ Set USB timeout.
-
std::chrono::milliseconds
getUsbTimeout
()¶ Get USB timeout.
-
void
setNetworkTimeout
(std::chrono::milliseconds ms)¶ Set NETWOR timeout.
-
std::chrono::milliseconds
getNetworkTimeout
()¶ Get NETWORK timeout.
-
void
setMacAddress
(std::string mac)¶ Set MAC address if not flashed on controller.
-
std::string
getMacAddress
()¶ Get MAC address if not flashed on controller.
-
nlohmann::json
toJson
() const¶ To JSON.
-
void
-
struct
MemoryInfo
¶
-
-
struct
DeviceInfo
¶ - #include <XLinkConnection.hpp>
Describes a connected device
Public Functions
-
DeviceInfo
(std::string mxidOrName)¶ Creates a DeviceInfo by checking whether supplied parameter is a MXID or IP/USB name
- Parameters
mxidOrName
: Either MXID, IP Address or USB port name
-
-
class
EdgeDetectorConfig
: public dai::Buffer - #include <EdgeDetectorConfig.hpp>
EdgeDetectorConfig message. Carries sobel edge filter config.
Public Functions
-
EdgeDetectorConfig
() Construct EdgeDetectorConfig message.
-
void
setSobelFilterKernels
(const std::vector<std::vector<int>> &horizontalKernel, const std::vector<std::vector<int>> &verticalKernel) Set sobel filter horizontal and vertical 3x3 kernels
- Parameters
horizontalKernel
: Used for horizontal gradient computation in 3x3 Sobel filterverticalKernel
: Used for vertical gradient computation in 3x3 Sobel filter
-
EdgeDetectorConfigData
getConfigData
() const Retrieve configuration data for EdgeDetector
- Return
EdgeDetectorConfigData: sobel filter horizontal and vertical 3x3 kernels
-
EdgeDetectorConfig &
set
(dai::RawEdgeDetectorConfig config) Set explicit configuration.
- Parameters
config
: Explicit configuration
-
dai::RawEdgeDetectorConfig
get
() const Retrieve configuration data for EdgeDetector.
- Return
config for EdgeDetector
-
-
struct
EdgeDetectorConfigData
¶ - #include <RawEdgeDetectorConfig.hpp>
EdgeDetectorConfigData configuration data structure.
Public Members
-
std::vector<std::vector<int>>
sobelFilterHorizontalKernel
¶ Used for horizontal gradient computation in 3x3 Sobel filter Format - 3x3 matrix, 2nd column must be 0 Default - +1 0 -1; +2 0 -2; +1 0 -1
-
std::vector<std::vector<int>>
sobelFilterVerticalKernel
¶ Used for vertical gradient computation in 3x3 Sobel filter Format - 3x3 matrix, 2nd row must be 0 Default - +1 +2 +1; 0 0 0; -1 -2 -1
-
std::vector<std::vector<int>>
-
struct
EdgeDetectorProperties
: public dai::PropertiesSerializable<Properties, EdgeDetectorProperties>¶ - #include <EdgeDetectorProperties.hpp>
Specify properties for EdgeDetector
Public Members
-
RawEdgeDetectorConfig
initialConfig
¶ Initial edge detector config.
-
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.
-
RawEdgeDetectorConfig
-
struct
EepromData
¶ - #include <EepromData.hpp>
EepromData structure
Contains the Calibration and Board data stored on device
Public Members
-
uint64_t
batchTime
= {0}¶ Deprecated, not used or stored.
-
uint64_t
-
struct
EepromError
: public runtime_error¶
-
class
EncodedFrame
: public dai::Buffer Public Functions
-
EncodedFrame
() Construct EncodedFrame message. Timestamp is set to now
-
unsigned int
getInstanceNum
() const Retrieves instance number
-
std::chrono::microseconds
getExposureTime
() const Retrieves exposure time
-
int
getSensitivity
() const Retrieves sensitivity, as an ISO value
-
int
getColorTemperature
() const Retrieves white-balance color temperature of the light source, in kelvins
-
int
getLensPosition
() const Retrieves lens position, range 0..255. Returns -1 if not available
-
float
getLensPositionRaw
() const Retrieves lens position, range 0.0f..1.0f. Returns -1 if not available
-
unsigned int
getQuality
() const Retrieves the encoding quality
-
unsigned int
getBitrate
() const Retrieves the encoding bitrate
-
bool
getLossless
() const Returns true if encoding is lossless (JPEG only)
-
FrameType
getFrameType
() const Retrieves frame type (H26x only)
-
Profile
getProfile
() const Retrieves the encoding profile (JPEG, AVC or HEVC)
-
EncodedFrame &
setTimestamp
(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> tp) Retrieves image timestamp related to dai::Clock::now()
-
EncodedFrame &
setTimestampDevice
(std::chrono::time_point<std::chrono::steady_clock, std::chrono::steady_clock::duration> tp) Sets image timestamp related to dai::Clock::now()
-
EncodedFrame &
setSequenceNum
(int64_t seq) Specifies sequence number
- Parameters
seq
: Sequence number
-
EncodedFrame &
setInstanceNum
(unsigned int instance) Instance number relates to the origin of the frame (which camera)
- Parameters
instance
: Instance number
-
EncodedFrame &
setQuality
(unsigned int quality) Specifies the encoding quality
- Parameters
quality
: Encoding quality
-
EncodedFrame &
setBitrate
(unsigned int bitrate) Specifies the encoding quality
- Parameters
quality
: Encoding quality
-
EncodedFrame &
setLossless
(bool lossless) Specifies if encoding is lossless (JPEG only)
- Parameters
lossless
: True if lossless
-
EncodedFrame &
setFrameType
(FrameType type) Specifies the frame type (H26x only)
- Parameters
type
: Type of h26x frame (I, P, B)
-
EncodedFrame &
setProfile
(Profile profile) Specifies the encoding profile
- Parameters
profile
: Encoding profile
-
-
struct
Extrinsics
¶ - #include <Extrinsics.hpp>
Extrinsics structure.
-
class
FeatureTrackerConfig
: public dai::Buffer - #include <FeatureTrackerConfig.hpp>
FeatureTrackerConfig message. Carries config for feature tracking algorithm
Public Functions
-
FeatureTrackerConfig
() Construct FeatureTrackerConfig message.
-
FeatureTrackerConfig &
setCornerDetector
(dai::FeatureTrackerConfig::CornerDetector::Type cornerDetector) Set corner detector algorithm type.
- Parameters
cornerDetector
: Corner detector type, HARRIS or SHI_THOMASI
-
FeatureTrackerConfig &
setCornerDetector
(dai::FeatureTrackerConfig::CornerDetector config) Set corner detector full configuration.
- Parameters
config
: Corner detector configuration
-
FeatureTrackerConfig &
setOpticalFlow
() Set optical flow as motion estimation algorithm type.
-
FeatureTrackerConfig &
setOpticalFlow
(dai::FeatureTrackerConfig::MotionEstimator::OpticalFlow config) Set optical flow full configuration.
- Parameters
config
: Optical flow configuration
-
FeatureTrackerConfig &
setHwMotionEstimation
() Set hardware accelerated motion estimation using block matching. Faster than optical flow (software implementation) but might not be as accurate.
-
FeatureTrackerConfig &
setNumTargetFeatures
(std::int32_t numTargetFeatures) Set number of target features to detect.
- Parameters
numTargetFeatures
: Number of features
-
FeatureTrackerConfig &
setMotionEstimator
(bool enable) Enable or disable motion estimator.
- Parameters
enable
:
-
FeatureTrackerConfig &
setMotionEstimator
(dai::FeatureTrackerConfig::MotionEstimator config) Set motion estimator full configuration.
- Parameters
config
: Motion estimator configuration
-
FeatureTrackerConfig &
setFeatureMaintainer
(bool enable) Enable or disable feature maintainer.
- Parameters
enable
:
-
FeatureTrackerConfig &
setFeatureMaintainer
(dai::FeatureTrackerConfig::FeatureMaintainer config) Set feature maintainer full configuration.
- Parameters
config
: feature maintainer configuration
-
FeatureTrackerConfig &
set
(dai::RawFeatureTrackerConfig config) Set explicit configuration.
- Parameters
config
: Explicit configuration
-
dai::RawFeatureTrackerConfig
get
() const Retrieve configuration data for FeatureTracker.
- Return
config for feature tracking algorithm
-
-
struct
FeatureTrackerProperties
: public dai::PropertiesSerializable<Properties, FeatureTrackerProperties>¶ - #include <FeatureTrackerProperties.hpp>
Specify properties for FeatureTracker
Public Members
-
RawFeatureTrackerConfig
initialConfig
¶ Initial feature tracker config
-
std::int32_t
numShaves
= 1¶ Number of shaves reserved for feature tracking. Optical flow can use 1 or 2 shaves, while for corner detection only 1 is enough. Hardware motion estimation doesn’t require shaves. Maximum 2, minimum 1.
-
std::int32_t
numMemorySlices
= 1¶ Number of memory slices reserved for feature tracking. Optical flow can use 1 or 2 memory slices, while for corner detection only 1 is enough. Maximum number of features depends on the number of allocated memory slices. Hardware motion estimation doesn’t require memory slices. Maximum 2, minimum 1.
-
RawFeatureTrackerConfig
-
struct
GlobalProperties
: public dai::PropertiesSerializable<Properties, 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
-
tl::optional<dai::EepromData>
calibData
¶ Calibration data sent through pipeline
-
tl::optional<std::uint32_t>
cameraTuningBlobSize
¶ Camera tuning blob size in bytes
-
std::string
cameraTuningBlobUri
¶ Uri which points to camera tuning blob
-
int32_t
xlinkChunkSize
= -1¶ Chunk size for splitting device-sent XLink packets, in bytes. A larger value could increase performance, with 0 disabling chunking. A negative value won’t modify the device defaults - configured per protocol, currently 64*1024 for both USB and Ethernet.
-
uint32_t
sippBufferSize
= SIPP_BUFFER_DEFAULT_SIZE¶ SIPP (Signal Image Processing Pipeline) internal memory pool. SIPP is a framework used to schedule HW filters, e.g. ISP, Warp, Median filter etc. Changing the size of this pool is meant for advanced use cases, pushing the limits of the HW. By default memory is allocated in high speed CMX memory. Setting to 0 will allocate in DDR 256 kilobytes. Units are bytes.
-
uint32_t
sippDmaBufferSize
= SIPP_DMA_BUFFER_DEFAULT_SIZE¶ SIPP (Signal Image Processing Pipeline) internal DMA memory pool. SIPP is a framework used to schedule HW filters, e.g. ISP, Warp, Median filter etc. Changing the size of this pool is meant for advanced use cases, pushing the limits of the HW. Memory is allocated in high speed CMX memory Units are bytes.
-
double
-
class
ImageAlignConfig
: public dai::Buffer - #include <ImageAlignConfig.hpp>
ImageAlignConfig message
Public Functions
-
ImageAlignConfig &
set
(dai::RawImageAlignConfig config)¶ Set explicit configuration.
- Parameters
config
: Explicit configuration
-
dai::RawImageAlignConfig
get
() const¶ Retrieve configuration data for SpatialLocationCalculator.
- Return
config for SpatialLocationCalculator
-
ImageAlignConfig &
-
struct
ImageAlignProperties
: public dai::PropertiesSerializable<Properties, ImageAlignProperties>¶ - #include <ImageAlignProperties.hpp>
Specify properties for ImageAlign
Public Members
-
int
numFramesPool
= 4¶ Num frames in output pool.
-
int
alignWidth
= 0¶ Optional output width
-
int
alignHeight
= 0¶ Optional output height
-
std::vector<int>
warpHwIds
¶ Warp HW IDs to use, if empty, use auto/default.
-
Interpolation
interpolation
= Interpolation::AUTO¶ Interpolation type to use.
-
bool
outKeepAspectRatio
= true¶ Whether to keep aspect ratio of the input or not
-
std::int32_t
numShaves
= 2¶ Number of shaves reserved.
-
int
-
class
ImageManipConfig
:
-
using