#include <Device.hpp>
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< DataInputQueue > | getInputQueue (const std::string &name) |
std::shared_ptr< DataInputQueue > | getInputQueue (const std::string &name, unsigned int maxSize, bool blocking=true) |
std::vector< std::string > | getInputQueueNames () const |
std::shared_ptr< DataOutputQueue > | getOutputQueue (const std::string &name) |
std::shared_ptr< DataOutputQueue > | getOutputQueue (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... | |
![]() | |
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< StereoPair > | getAvailableStereoPairs () |
tl::optional< Version > | getBootloaderVersion () |
CalibrationHandler | getCalibration () |
std::unordered_map< CameraBoardSocket, std::string > | getCameraSensorNames () |
ChipTemperature | getChipTemperature () |
MemoryInfo | getCmxMemoryUsage () |
std::vector< CameraFeatures > | getConnectedCameraFeatures () |
std::vector< CameraBoardSocket > | getConnectedCameras () |
std::string | getConnectedIMU () |
std::shared_ptr< XLinkConnection > | getConnection () |
std::shared_ptr< const XLinkConnection > | getConnection () const |
std::vector< ConnectionInterface > | getConnectionInterfaces () |
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< StereoPair > | getStereoPairs () |
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 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::CallbackId > | callbackIdMap |
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 std::vector< DeviceInfo > | getAllAvailableDevices () |
static std::vector< DeviceInfo > | getAllConnectedDevices () |
static std::tuple< bool, DeviceInfo > | getAnyAvailableDevice () |
static std::tuple< bool, DeviceInfo > | getAnyAvailableDevice (std::chrono::milliseconds timeout) |
static std::tuple< bool, DeviceInfo > | getAnyAvailableDevice (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, DeviceInfo > | getDeviceByMxId (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, DeviceInfo > | getFirstAvailableDevice (bool skipInvalidDevice=true) |
static ProfilingData | getGlobalProfilingData () |
![]() | |
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... | |
![]() | |
std::shared_ptr< XLinkConnection > | connection |
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.
|
explicit |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
Definition at line 26 of file Device.cpp.
dai::Device::Device | ( | const Pipeline & | pipeline, |
T | usb2Mode | ||
) |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
usb2Mode | (bool) Boot device using USB2 mode firmware |
Definition at line 31 of file Device.cpp.
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 36 of file Device.cpp.
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
Definition at line 40 of file Device.cpp.
dai::Device::Device | ( | const Pipeline & | pipeline, |
const DeviceInfo & | devInfo | ||
) |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
Definition at line 44 of file Device.cpp.
dai::Device::Device | ( | const Pipeline & | pipeline, |
const DeviceInfo & | devInfo, | ||
T | usb2Mode | ||
) |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
usb2Mode | (bool) Boot device using USB2 mode firmware |
Definition at line 53 of file Device.cpp.
dai::Device::Device | ( | const Pipeline & | pipeline, |
const DeviceInfo & | devInfo, | ||
UsbSpeed | maxUsbSpeed | ||
) |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 58 of file Device.cpp.
dai::Device::Device | ( | const Pipeline & | pipeline, |
const DeviceInfo & | devInfo, | ||
const dai::Path & | pathToCmd | ||
) |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
pathToCmd | Path to custom device firmware |
Definition at line 48 of file Device.cpp.
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.
|
override |
dtor to close the device
Definition at line 64 of file Device.cpp.
|
overrideprivatevirtual |
Allows the derived classes to handle custom setup for gracefully stopping the pipeline
Reimplemented from dai::DeviceBase.
Definition at line 68 of file Device.cpp.
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.
|
explicit |
Connects to any available device with custom config.
config | Device custom configuration to boot with |
Definition at line 507 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
config | Config with which the device will be booted with |
pathToCmd | Path to custom device firmware |
Definition at line 414 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device 'devInfo' with custom config.
config | Device custom configuration to boot with |
devInfo | DeviceInfo which specifies which device to connect to |
Definition at line 512 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
config | Config with which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
pathToCmd | Path to custom device firmware |
dumpOnly | If true only the minimal connection is established to retrieve the crash dump |
Definition at line 410 of file DeviceBase.cpp.
|
inline |
Connects to device specified by devInfo.
config | Config with which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 366 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
config | Config with which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 406 of file DeviceBase.cpp.
|
inline |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
config | Config with which the device will be booted with |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 343 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
config | Config with which the device will be booted with |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 418 of file DeviceBase.cpp.
|
explicit |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
devInfo | DeviceInfo which specifies which device to connect to |
Definition at line 355 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
devInfo | DeviceInfo which specifies which device to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 357 of file DeviceBase.cpp.
|
explicit |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
Definition at line 376 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
Definition at line 386 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
Definition at line 391 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
pathToCmd | Path to custom device firmware |
Definition at line 401 of file DeviceBase.cpp.
|
inline |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 204 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
pipeline | Pipeline to be executed on the device |
devInfo | DeviceInfo which specifies which device to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 396 of file DeviceBase.cpp.
|
inline |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 174 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
pipeline | Pipeline to be executed on the device |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 381 of file DeviceBase.cpp.
|
explicit |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
version | OpenVINO version which the device will be booted with. |
Definition at line 364 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
version | OpenVINO version which the device will be booted with |
pathToCmd | Path to custom device firmware |
Definition at line 368 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
version | OpenVINO version which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
Definition at line 340 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
version | OpenVINO version which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
pathToCmd | Path to custom device firmware |
Definition at line 346 of file DeviceBase.cpp.
|
inline |
Connects to device specified by devInfo.
version | OpenVINO version which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 271 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
version | OpenVINO version which the device will be booted with |
devInfo | DeviceInfo which specifies which device to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 342 of file DeviceBase.cpp.
|
inline |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
version | OpenVINO version which the device will be booted with |
usb2Mode | Boot device using USB2 mode firmware |
Definition at line 241 of file DeviceBase.hpp.
dai::DeviceBase::DeviceBase |
Connects to device specified by devInfo.
version | OpenVINO version which the device will be booted with |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 372 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
nameOrDeviceId | Creates DeviceInfo with nameOrDeviceId to connect to |
Definition at line 359 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase |
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
nameOrDeviceId | Creates DeviceInfo with nameOrDeviceId to connect to |
maxUsbSpeed | Maximum allowed USB speed |
Definition at line 361 of file DeviceBase.cpp.
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
name | Queue/stream name, set in XLinkIn node |
Definition at line 120 of file Device.cpp.
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
name | Queue/stream name, set in XLinkIn node |
maxSize | Maximum number of messages in queue |
blocking | Queue behavior once full. True: blocking, false: overwriting of oldest messages. Default: true |
Definition at line 130 of file Device.cpp.
std::vector< std::string > dai::Device::getInputQueueNames | ( | ) | const |
Get all available input queue names
Definition at line 145 of file Device.cpp.
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
name | Queue/stream name, created by XLinkOut node |
Definition at line 86 of file Device.cpp.
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
name | Queue/stream name, set in XLinkOut node |
maxSize | Maximum number of messages in queue |
blocking | Queue behavior once full. True specifies blocking and false overwriting of oldest messages. Default: true |
Definition at line 96 of file Device.cpp.
std::vector< std::string > dai::Device::getOutputQueueNames | ( | ) | const |
Get all available output queue names
Definition at line 111 of file Device.cpp.
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.
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
queueNames | Names of queues for which to wait for |
timeout | Timeout after which return regardless. If negative then wait is indefinite. Default is -1 |
Definition at line 238 of file Device.cpp.
std::string dai::Device::getQueueEvent | ( | std::chrono::microseconds | timeout = std::chrono::microseconds(-1) | ) |
Gets or waits until any queue has received a message
timeout | Timeout after which return regardless. If negative then wait is indefinite. Default is -1 |
Definition at line 251 of file Device.cpp.
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
queueNames | Name of queues for which to wait for |
timeout | Timeout after which return regardless. If negative then wait is indefinite. Default is -1 |
Definition at line 247 of file Device.cpp.
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.
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
queueNames | Names of queues for which to block |
maxNumEvents | Maximum number of events to remove from queue - Default is unlimited |
timeout | Timeout after which return regardless. If negative then wait is indefinite - Default is -1 |
Definition at line 164 of file Device.cpp.
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
maxNumEvents | Maximum number of events to remove from queue. Default is unlimited |
timeout | Timeout after which return regardless. If negative then wait is indefinite. Default is -1 |
Definition at line 234 of file Device.cpp.
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
queueName | Name of queues for which to wait for |
maxNumEvents | Maximum number of events to remove from queue. Default is unlimited |
timeout | Timeout after which return regardless. If negative then wait is indefinite. Default is -1 |
Definition at line 230 of file Device.cpp.
|
overrideprivatevirtual |
Allows the derived classes to handle custom setup for starting the pipeline
pipeline | OpenVINO version of the pipeline must match the one which the device was booted with |
Reimplemented from dai::DeviceBase.
Definition at line 255 of file Device.cpp.
|
private |
Definition at line 218 of file Device.hpp.
|
staticconstexpr |
Maximum number of elements in event queue.
Definition at line 97 of file Device.hpp.
|
private |
Definition at line 222 of file Device.hpp.
|
private |
Definition at line 221 of file Device.hpp.
|
private |
Definition at line 223 of file Device.hpp.
|
private |
Definition at line 217 of file Device.hpp.
|
private |
Definition at line 216 of file Device.hpp.