Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
dai::Device Class Reference

#include <Device.hpp>

Inheritance diagram for dai::Device:
Inheritance graph
[legend]

Public Member Functions

 Device ()
 
 Device (const Pipeline &pipeline)
 
 Device (const Pipeline &pipeline, const dai::Path &pathToCmd)
 
 Device (const Pipeline &pipeline, const DeviceInfo &devInfo)
 
 Device (const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 Device (const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode)
 
 Device (const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 Device (const Pipeline &pipeline, T usb2Mode)
 
 Device (const Pipeline &pipeline, UsbSpeed maxUsbSpeed)
 
 DeviceBase ()
 
 DeviceBase (Config config)
 
 DeviceBase (Config config, const dai::Path &pathToCmd)
 
 DeviceBase (Config config, const DeviceInfo &devInfo)
 
 DeviceBase (Config config, const DeviceInfo &devInfo, const dai::Path &pathToCmd, bool dumpOnly=false)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (Config config, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (Config config, T usb2Mode)
 
 DeviceBase (Config config, UsbSpeed maxUsbSpeed)
 
 DeviceBase (const DeviceInfo &devInfo)
 
 DeviceBase (const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
 DeviceBase (const Pipeline &pipeline)
 
 DeviceBase (const Pipeline &pipeline, const dai::Path &pathToCmd)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (const Pipeline &pipeline, T usb2Mode)
 
 DeviceBase (const Pipeline &pipeline, UsbSpeed maxUsbSpeed)
 
 DeviceBase (OpenVINO::Version version)
 
 DeviceBase (OpenVINO::Version version, const dai::Path &pathToCmd)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (OpenVINO::Version version, T usb2Mode)
 
 DeviceBase (OpenVINO::Version version, UsbSpeed maxUsbSpeed)
 
 DeviceBase (std::string nameOrDeviceId)
 
 DeviceBase (std::string nameOrDeviceId, UsbSpeed maxUsbSpeed)
 
std::shared_ptr< DataInputQueuegetInputQueue (const std::string &name)
 
std::shared_ptr< DataInputQueuegetInputQueue (const std::string &name, unsigned int maxSize, bool blocking=true)
 
std::vector< std::string > getInputQueueNames () const
 
std::shared_ptr< DataOutputQueuegetOutputQueue (const std::string &name)
 
std::shared_ptr< DataOutputQueuegetOutputQueue (const std::string &name, unsigned int maxSize, bool blocking=true)
 
std::vector< std::string > getOutputQueueNames () const
 
std::string getQueueEvent (const std::initializer_list< std::string > &queueNames, std::chrono::microseconds timeout=std::chrono::microseconds(-1))
 
std::string getQueueEvent (const std::vector< std::string > &queueNames, std::chrono::microseconds timeout=std::chrono::microseconds(-1))
 
std::string getQueueEvent (std::chrono::microseconds timeout=std::chrono::microseconds(-1))
 
std::string getQueueEvent (std::string queueName, std::chrono::microseconds timeout=std::chrono::microseconds(-1))
 
std::vector< std::string > getQueueEvents (const std::initializer_list< std::string > &queueNames, std::size_t maxNumEvents=std::numeric_limits< std::size_t >::max(), std::chrono::microseconds timeout=std::chrono::microseconds(-1))
 
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))
 
std::vector< std::string > getQueueEvents (std::size_t maxNumEvents=std::numeric_limits< std::size_t >::max(), std::chrono::microseconds timeout=std::chrono::microseconds(-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))
 
 ~Device () override
 dtor to close the device More...
 
- Public Member Functions inherited from dai::DeviceBase
int addLogCallback (std::function< void(LogMessage)> callback)
 
void close ()
 
 DeviceBase ()
 
 DeviceBase (Config config)
 
 DeviceBase (Config config, const dai::Path &pathToCmd)
 
 DeviceBase (Config config, const DeviceInfo &devInfo)
 
 DeviceBase (Config config, const DeviceInfo &devInfo, const dai::Path &pathToCmd, bool dumpOnly=false)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (Config config, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (Config config, T usb2Mode)
 
 DeviceBase (Config config, UsbSpeed maxUsbSpeed)
 
 DeviceBase (const DeviceInfo &devInfo)
 
 DeviceBase (const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
 DeviceBase (const Pipeline &pipeline)
 
 DeviceBase (const Pipeline &pipeline, const dai::Path &pathToCmd)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (const Pipeline &pipeline, T usb2Mode)
 
 DeviceBase (const Pipeline &pipeline, UsbSpeed maxUsbSpeed)
 
 DeviceBase (OpenVINO::Version version)
 
 DeviceBase (OpenVINO::Version version, const dai::Path &pathToCmd)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, T usb2Mode)
 
 DeviceBase (OpenVINO::Version version, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBase (OpenVINO::Version version, T usb2Mode)
 
 DeviceBase (OpenVINO::Version version, UsbSpeed maxUsbSpeed)
 
 DeviceBase (std::string nameOrDeviceId)
 
 DeviceBase (std::string nameOrDeviceId, UsbSpeed maxUsbSpeed)
 
void factoryResetCalibration ()
 
bool flashCalibration (CalibrationHandler calibrationDataHandler)
 
void flashCalibration2 (CalibrationHandler calibrationDataHandler)
 
void flashEepromClear ()
 
void flashFactoryCalibration (CalibrationHandler calibrationHandler)
 
void flashFactoryEepromClear ()
 
std::vector< StereoPairgetAvailableStereoPairs ()
 
tl::optional< VersiongetBootloaderVersion ()
 
CalibrationHandler getCalibration ()
 
std::unordered_map< CameraBoardSocket, std::string > getCameraSensorNames ()
 
ChipTemperature getChipTemperature ()
 
MemoryInfo getCmxMemoryUsage ()
 
std::vector< CameraFeaturesgetConnectedCameraFeatures ()
 
std::vector< CameraBoardSocketgetConnectedCameras ()
 
std::string getConnectedIMU ()
 
std::shared_ptr< XLinkConnectiongetConnection ()
 
std::shared_ptr< const XLinkConnectiongetConnection () const
 
std::vector< ConnectionInterfacegetConnectionInterfaces ()
 
dai::CrashDump getCrashDump (bool clearCrashDump=true)
 
MemoryInfo getDdrMemoryUsage ()
 
DeviceInfo getDeviceInfo () const
 
std::string getDeviceName ()
 
dai::Version getEmbeddedIMUFirmwareVersion ()
 
std::tuple< bool, unsigned int > getIMUFirmwareUpdateStatus ()
 
dai::Version getIMUFirmwareVersion ()
 
std::vector< std::tuple< std::string, int, int > > getIrDrivers ()
 
CpuUsage getLeonCssCpuUsage ()
 
MemoryInfo getLeonCssHeapUsage ()
 
CpuUsage getLeonMssCpuUsage ()
 
MemoryInfo getLeonMssHeapUsage ()
 
LogLevel getLogLevel ()
 
LogLevel getLogOutputLevel ()
 
std::string getMxId ()
 
std::string getProductName ()
 
ProfilingData getProfilingData ()
 
std::vector< StereoPairgetStereoPairs ()
 
float getSystemInformationLoggingRate ()
 
UsbSpeed getUsbSpeed ()
 
int getXLinkChunkSize ()
 
bool hasCrashDump ()
 
bool isClosed () const
 
bool isEepromAvailable ()
 
bool isPipelineRunning ()
 
CalibrationHandler readCalibration ()
 
CalibrationHandler readCalibration2 ()
 
CalibrationHandler readCalibrationOrDefault ()
 
std::vector< std::uint8_t > readCalibrationRaw ()
 
CalibrationHandler readFactoryCalibration ()
 
CalibrationHandler readFactoryCalibrationOrDefault ()
 
std::vector< std::uint8_t > readFactoryCalibrationRaw ()
 
bool removeLogCallback (int callbackId)
 
void setCalibration (CalibrationHandler calibrationDataHandler)
 
bool setIrFloodLightBrightness (float mA, int mask=-1)
 
bool setIrFloodLightIntensity (float intensity, int mask=-1)
 
bool setIrLaserDotProjectorBrightness (float mA, int mask=-1)
 
bool setIrLaserDotProjectorIntensity (float intensity, int mask=-1)
 
void setLogLevel (LogLevel level)
 
void setLogOutputLevel (LogLevel level)
 
void setSystemInformationLoggingRate (float rateHz)
 
void setTimesync (bool enable)
 
void setTimesync (std::chrono::milliseconds period, int numSamples, bool random)
 
void setXLinkChunkSize (int sizeBytes)
 
void setXLinkRateLimit (int maxRateBytesPerSecond, int burstSize=0, int waitUs=0)
 
bool startIMUFirmwareUpdate (bool forceUpdate=false)
 
bool startPipeline ()
 
bool startPipeline (const Pipeline &pipeline)
 
virtual ~DeviceBase ()
 

Static Public Attributes

static constexpr std::size_t EVENT_QUEUE_MAXIMUM_SIZE {2048}
 Maximum number of elements in event queue. More...
 
- Static Public Attributes inherited from dai::DeviceBase
static constexpr std::chrono::seconds DEFAULT_SEARCH_TIME {3}
 Default search time for constructors which discover devices. More...
 
static constexpr float DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ {1.0f}
 Default rate at which system information is logged. More...
 
static constexpr int DEFAULT_TIMESYNC_NUM_SAMPLES {10}
 Default Timesync number of samples per sync. More...
 
static constexpr std::chrono::milliseconds DEFAULT_TIMESYNC_PERIOD {5000}
 Default Timesync period. More...
 
static constexpr bool DEFAULT_TIMESYNC_RANDOM {true}
 Default Timesync packet interval randomness. More...
 
static constexpr UsbSpeed DEFAULT_USB_SPEED {UsbSpeed::SUPER}
 Default UsbSpeed for device connection. More...
 

Private Member Functions

void closeImpl () override
 
bool startPipelineImpl (const Pipeline &pipeline) override
 

Private Attributes

std::unordered_map< std::string, DataOutputQueue::CallbackIdcallbackIdMap
 
std::condition_variable eventCv
 
std::mutex eventMtx
 
std::deque< std::string > eventQueue
 
std::unordered_map< std::string, std::shared_ptr< DataInputQueue > > inputQueueMap
 
std::unordered_map< std::string, std::shared_ptr< DataOutputQueue > > outputQueueMap
 

Additional Inherited Members

- Static Public Member Functions inherited from dai::DeviceBase
static std::vector< DeviceInfogetAllAvailableDevices ()
 
static std::vector< DeviceInfogetAllConnectedDevices ()
 
static std::tuple< bool, DeviceInfogetAnyAvailableDevice ()
 
static std::tuple< bool, DeviceInfogetAnyAvailableDevice (std::chrono::milliseconds timeout)
 
static std::tuple< bool, DeviceInfogetAnyAvailableDevice (std::chrono::milliseconds timeout, std::function< void()> cb)
 
static std::chrono::milliseconds getDefaultSearchTime ()
 Get the Default Search Time for finding devices. More...
 
static std::tuple< bool, DeviceInfogetDeviceByMxId (std::string mxId)
 
static std::vector< std::uint8_t > getEmbeddedDeviceBinary (bool usb2Mode, OpenVINO::Version version=OpenVINO::VERSION_UNIVERSAL)
 
static std::vector< std::uint8_t > getEmbeddedDeviceBinary (Config config)
 
static std::tuple< bool, DeviceInfogetFirstAvailableDevice (bool skipInvalidDevice=true)
 
static ProfilingData getGlobalProfilingData ()
 
- Protected Member Functions inherited from dai::DeviceBase
void init (Config config, const dai::Path &pathToCmd)
 
void init (Config config, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
void init (Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
void init (Config config, UsbSpeed maxUsbSpeed)
 
void init (Config config, UsbSpeed maxUsbSpeed, const dai::Path &pathToMvcmd)
 
void init (const Pipeline &pipeline)
 
void init (const Pipeline &pipeline, const dai::Path &pathToCmd)
 
void init (const Pipeline &pipeline, const DeviceInfo &devInfo)
 
void init (const Pipeline &pipeline, const DeviceInfo &devInfo, bool usb2Mode)
 
void init (const Pipeline &pipeline, const DeviceInfo &devInfo, const dai::Path &pathToCmd)
 
void init (const Pipeline &pipeline, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
 
void init (const Pipeline &pipeline, UsbSpeed maxUsbSpeed)
 
void init (const Pipeline &pipeline, UsbSpeed maxUsbSpeed, const dai::Path &pathToMvcmd)
 
void init (OpenVINO::Version version)
 
void init (OpenVINO::Version version, const dai::Path &pathToCmd)
 
void init (OpenVINO::Version version, UsbSpeed maxUsbSpeed)
 
void init (OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path &pathToMvcmd)
 
void tryStartPipeline (const Pipeline &pipeline)
 a safe way to start a pipeline, which is closed if any exception occurs More...
 
- Protected Attributes inherited from dai::DeviceBase
std::shared_ptr< XLinkConnectionconnection
 

Detailed Description

Represents the DepthAI device with the methods to interact with it. Implements the host-side queues to connect with XLinkIn and XLinkOut nodes

Definition at line 21 of file Device.hpp.

Constructor & Destructor Documentation

◆ Device() [1/9]

dai::Device::Device ( const Pipeline pipeline)
explicit

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device

Definition at line 26 of file Device.cpp.

◆ Device() [2/9]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > >
dai::Device::Device ( const Pipeline pipeline,
usb2Mode 
)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
usb2Mode(bool) Boot device using USB2 mode firmware

Definition at line 31 of file Device.cpp.

◆ Device() [3/9]

dai::Device::Device ( const Pipeline pipeline,
UsbSpeed  maxUsbSpeed 
)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
maxUsbSpeedMaximum allowed USB speed

Definition at line 36 of file Device.cpp.

◆ Device() [4/9]

dai::Device::Device ( const Pipeline pipeline,
const dai::Path pathToCmd 
)

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
pathToCmdPath to custom device firmware

Definition at line 40 of file Device.cpp.

◆ Device() [5/9]

dai::Device::Device ( const Pipeline pipeline,
const DeviceInfo devInfo 
)

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to

Definition at line 44 of file Device.cpp.

◆ Device() [6/9]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > >
dai::Device::Device ( const Pipeline pipeline,
const DeviceInfo devInfo,
usb2Mode 
)

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
usb2Mode(bool) Boot device using USB2 mode firmware

Definition at line 53 of file Device.cpp.

◆ Device() [7/9]

dai::Device::Device ( const Pipeline pipeline,
const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 58 of file Device.cpp.

◆ Device() [8/9]

dai::Device::Device ( const Pipeline pipeline,
const DeviceInfo devInfo,
const dai::Path pathToCmd 
)

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
pathToCmdPath to custom device firmware

Definition at line 48 of file Device.cpp.

◆ Device() [9/9]

dai::Device::Device ( )

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Definition at line 62 of file Device.cpp.

◆ ~Device()

dai::Device::~Device ( )
override

dtor to close the device

Definition at line 64 of file Device.cpp.

Member Function Documentation

◆ closeImpl()

void dai::Device::closeImpl ( )
overrideprivatevirtual

Allows the derived classes to handle custom setup for gracefully stopping the pipeline

Note
Remember to call this function in the overload to setup the communication properly

Reimplemented from dai::DeviceBase.

Definition at line 68 of file Device.cpp.

◆ DeviceBase() [1/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Definition at line 353 of file DeviceBase.cpp.

◆ DeviceBase() [2/29]

dai::DeviceBase::DeviceBase
explicit

Connects to any available device with custom config.

Parameters
configDevice custom configuration to boot with

Definition at line 507 of file DeviceBase.cpp.

◆ DeviceBase() [3/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
configConfig with which the device will be booted with
pathToCmdPath to custom device firmware

Definition at line 414 of file DeviceBase.cpp.

◆ DeviceBase() [4/29]

dai::DeviceBase::DeviceBase

Connects to device 'devInfo' with custom config.

Parameters
configDevice custom configuration to boot with
devInfoDeviceInfo which specifies which device to connect to

Definition at line 512 of file DeviceBase.cpp.

◆ DeviceBase() [5/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
configConfig with which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
pathToCmdPath to custom device firmware
dumpOnlyIf true only the minimal connection is established to retrieve the crash dump

Definition at line 410 of file DeviceBase.cpp.

◆ DeviceBase() [6/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to device specified by devInfo.

Parameters
configConfig with which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
usb2ModeBoot device using USB2 mode firmware

Definition at line 366 of file DeviceBase.hpp.

◆ DeviceBase() [7/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
configConfig with which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 406 of file DeviceBase.cpp.

◆ DeviceBase() [8/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
configConfig with which the device will be booted with
usb2ModeBoot device using USB2 mode firmware

Definition at line 343 of file DeviceBase.hpp.

◆ DeviceBase() [9/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
configConfig with which the device will be booted with
maxUsbSpeedMaximum allowed USB speed

Definition at line 418 of file DeviceBase.cpp.

◆ DeviceBase() [10/29]

dai::DeviceBase::DeviceBase
explicit

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Parameters
devInfoDeviceInfo which specifies which device to connect to

Definition at line 355 of file DeviceBase.cpp.

◆ DeviceBase() [11/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Parameters
devInfoDeviceInfo which specifies which device to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 357 of file DeviceBase.cpp.

◆ DeviceBase() [12/29]

dai::DeviceBase::DeviceBase
explicit

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device

Definition at line 376 of file DeviceBase.cpp.

◆ DeviceBase() [13/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
pathToCmdPath to custom device firmware

Definition at line 386 of file DeviceBase.cpp.

◆ DeviceBase() [14/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to

Definition at line 391 of file DeviceBase.cpp.

◆ DeviceBase() [15/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
pathToCmdPath to custom device firmware

Definition at line 401 of file DeviceBase.cpp.

◆ DeviceBase() [16/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
usb2ModeBoot device using USB2 mode firmware

Definition at line 204 of file DeviceBase.hpp.

◆ DeviceBase() [17/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
pipelinePipeline to be executed on the device
devInfoDeviceInfo which specifies which device to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 396 of file DeviceBase.cpp.

◆ DeviceBase() [18/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
usb2ModeBoot device using USB2 mode firmware

Definition at line 174 of file DeviceBase.hpp.

◆ DeviceBase() [19/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
pipelinePipeline to be executed on the device
maxUsbSpeedMaximum allowed USB speed

Definition at line 381 of file DeviceBase.cpp.

◆ DeviceBase() [20/29]

dai::DeviceBase::DeviceBase
explicit

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
versionOpenVINO version which the device will be booted with.

Definition at line 364 of file DeviceBase.cpp.

◆ DeviceBase() [21/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
versionOpenVINO version which the device will be booted with
pathToCmdPath to custom device firmware

Definition at line 368 of file DeviceBase.cpp.

◆ DeviceBase() [22/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
versionOpenVINO version which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to

Definition at line 340 of file DeviceBase.cpp.

◆ DeviceBase() [23/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
versionOpenVINO version which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
pathToCmdPath to custom device firmware

Definition at line 346 of file DeviceBase.cpp.

◆ DeviceBase() [24/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to device specified by devInfo.

Parameters
versionOpenVINO version which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
usb2ModeBoot device using USB2 mode firmware

Definition at line 271 of file DeviceBase.hpp.

◆ DeviceBase() [25/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
versionOpenVINO version which the device will be booted with
devInfoDeviceInfo which specifies which device to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 342 of file DeviceBase.cpp.

◆ DeviceBase() [26/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( typename T  ,
std::enable_if_t< std::is_same< T, bool >::value, bool >  = true 
)
inline

Connects to any available device with a DEFAULT_SEARCH_TIME timeout.

Parameters
versionOpenVINO version which the device will be booted with
usb2ModeBoot device using USB2 mode firmware

Definition at line 241 of file DeviceBase.hpp.

◆ DeviceBase() [27/29]

dai::DeviceBase::DeviceBase

Connects to device specified by devInfo.

Parameters
versionOpenVINO version which the device will be booted with
maxUsbSpeedMaximum allowed USB speed

Definition at line 372 of file DeviceBase.cpp.

◆ DeviceBase() [28/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Parameters
nameOrDeviceIdCreates DeviceInfo with nameOrDeviceId to connect to

Definition at line 359 of file DeviceBase.cpp.

◆ DeviceBase() [29/29]

dai::DeviceBase::DeviceBase

Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL

Parameters
nameOrDeviceIdCreates DeviceInfo with nameOrDeviceId to connect to
maxUsbSpeedMaximum allowed USB speed

Definition at line 361 of file DeviceBase.cpp.

◆ getInputQueue() [1/2]

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

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

Parameters
nameQueue/stream name, set in XLinkIn node
Returns
Smart pointer to DataInputQueue

Definition at line 120 of file Device.cpp.

◆ getInputQueue() [2/2]

std::shared_ptr< DataInputQueue > dai::Device::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

Parameters
nameQueue/stream name, set in XLinkIn node
maxSizeMaximum number of messages in queue
blockingQueue behavior once full. True: blocking, false: overwriting of oldest messages. Default: true
Returns
Smart pointer to DataInputQueue

Definition at line 130 of file Device.cpp.

◆ getInputQueueNames()

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

Get all available input queue names

Returns
Vector of input queue names

Definition at line 145 of file Device.cpp.

◆ getOutputQueue() [1/2]

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

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

Parameters
nameQueue/stream name, created by XLinkOut node
Returns
Smart pointer to DataOutputQueue

Definition at line 86 of file Device.cpp.

◆ getOutputQueue() [2/2]

std::shared_ptr< DataOutputQueue > dai::Device::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

Parameters
nameQueue/stream name, set in XLinkOut node
maxSizeMaximum number of messages in queue
blockingQueue behavior once full. True specifies blocking and false overwriting of oldest messages. Default: true
Returns
Smart pointer to DataOutputQueue

Definition at line 96 of file Device.cpp.

◆ getOutputQueueNames()

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

Get all available output queue names

Returns
Vector of output queue names

Definition at line 111 of file Device.cpp.

◆ getQueueEvent() [1/4]

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

Definition at line 243 of file Device.cpp.

◆ getQueueEvent() [2/4]

std::string dai::Device::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

Parameters
queueNamesNames of queues for which to wait for
timeoutTimeout after which return regardless. If negative then wait is indefinite. Default is -1
Returns
Queue name which received a message first

Definition at line 238 of file Device.cpp.

◆ getQueueEvent() [3/4]

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

Gets or waits until any queue has received a message

Parameters
timeoutTimeout after which return regardless. If negative then wait is indefinite. Default is -1
Returns
Queue name which received a message

Definition at line 251 of file Device.cpp.

◆ getQueueEvent() [4/4]

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

Gets or waits until specified queue has received a message

Parameters
queueNamesName of queues for which to wait for
timeoutTimeout after which return regardless. If negative then wait is indefinite. Default is -1
Returns
Queue name which received a message

Definition at line 247 of file Device.cpp.

◆ getQueueEvents() [1/4]

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

Definition at line 224 of file Device.cpp.

◆ getQueueEvents() [2/4]

std::vector< std::string > dai::Device::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

Parameters
queueNamesNames of queues for which to block
maxNumEventsMaximum number of events to remove from queue - Default is unlimited
timeoutTimeout after which return regardless. If negative then wait is indefinite - Default is -1
Returns
Names of queues which received messages first

Definition at line 164 of file Device.cpp.

◆ getQueueEvents() [3/4]

std::vector< std::string > dai::Device::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

Parameters
maxNumEventsMaximum number of events to remove from queue. Default is unlimited
timeoutTimeout after which return regardless. If negative then wait is indefinite. Default is -1
Returns
Names of queues which received messages first

Definition at line 234 of file Device.cpp.

◆ getQueueEvents() [4/4]

std::vector< std::string > dai::Device::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

Parameters
queueNameName of queues for which to wait for
maxNumEventsMaximum number of events to remove from queue. Default is unlimited
timeoutTimeout after which return regardless. If negative then wait is indefinite. Default is -1
Returns
Names of queues which received messages first

Definition at line 230 of file Device.cpp.

◆ startPipelineImpl()

bool dai::Device::startPipelineImpl ( const Pipeline pipeline)
overrideprivatevirtual

Allows the derived classes to handle custom setup for starting the pipeline

Parameters
pipelineOpenVINO version of the pipeline must match the one which the device was booted with
See also
startPipeline
Note
Remember to call this function in the overload to setup the communication properly
Returns
True if pipeline started, false otherwise

Reimplemented from dai::DeviceBase.

Definition at line 255 of file Device.cpp.

Member Data Documentation

◆ callbackIdMap

std::unordered_map<std::string, DataOutputQueue::CallbackId> dai::Device::callbackIdMap
private

Definition at line 218 of file Device.hpp.

◆ EVENT_QUEUE_MAXIMUM_SIZE

constexpr std::size_t dai::Device::EVENT_QUEUE_MAXIMUM_SIZE {2048}
staticconstexpr

Maximum number of elements in event queue.

Definition at line 97 of file Device.hpp.

◆ eventCv

std::condition_variable dai::Device::eventCv
private

Definition at line 222 of file Device.hpp.

◆ eventMtx

std::mutex dai::Device::eventMtx
private

Definition at line 221 of file Device.hpp.

◆ eventQueue

std::deque<std::string> dai::Device::eventQueue
private

Definition at line 223 of file Device.hpp.

◆ inputQueueMap

std::unordered_map<std::string, std::shared_ptr<DataInputQueue> > dai::Device::inputQueueMap
private

Definition at line 217 of file Device.hpp.

◆ outputQueueMap

std::unordered_map<std::string, std::shared_ptr<DataOutputQueue> > dai::Device::outputQueueMap
private

Definition at line 216 of file Device.hpp.


The documentation for this class was generated from the following files:


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:20