Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
dai::DeviceBase Class Reference

#include <DeviceBase.hpp>

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

Classes

struct  Config
 
class  Impl
 

Public Member Functions

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 Member Functions

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 ()
 

Static Public Attributes

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...
 

Protected Member Functions

virtual void closeImpl ()
 
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)
 
virtual bool startPipelineImpl (const Pipeline &pipeline)
 
void tryStartPipeline (const Pipeline &pipeline)
 a safe way to start a pipeline, which is closed if any exception occurs More...
 

Protected Attributes

std::shared_ptr< XLinkConnectionconnection
 

Private Member Functions

void init2 (Config cfg, const dai::Path &pathToMvcmd, tl::optional< const Pipeline & > pipeline)
 
void tryGetDevice ()
 

Private Attributes

tl::optional< VersionbootloaderVersion
 
bool closed {false}
 
std::mutex closedMtx
 
Config config
 
DeviceInfo deviceInfo = {}
 
bool dumpOnly = false
 
dai::Path firmwarePath
 
std::chrono::steady_clock::time_point lastWatchdogPingTime
 
std::mutex lastWatchdogPingTimeMtx
 
std::unordered_map< int, std::function< void(LogMessage)> > logCallbackMap
 
std::mutex logCallbackMapMtx
 
std::atomic< bool > loggingRunning {true}
 
std::thread loggingThread
 
std::thread monitorThread
 
Pimpl< Implpimpl
 
tl::optional< PipelineSchemapipelineSchema
 
std::atomic< bool > profilingRunning {true}
 
std::thread profilingThread
 
std::atomic< bool > timesyncRunning {true}
 
std::thread timesyncThread
 
int uniqueCallbackId = 0
 
std::atomic< bool > watchdogRunning {true}
 
std::thread watchdogThread
 

Detailed Description

The core of depthai device for RAII, connects to device and maintains watchdog, timesync, ...

Definition at line 50 of file DeviceBase.hpp.

Constructor & Destructor Documentation

◆ DeviceBase() [1/29]

dai::DeviceBase::DeviceBase ( 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 376 of file DeviceBase.cpp.

◆ DeviceBase() [2/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( const Pipeline pipeline,
usb2Mode 
)
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() [3/29]

dai::DeviceBase::DeviceBase ( 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 381 of file DeviceBase.cpp.

◆ DeviceBase() [4/29]

dai::DeviceBase::DeviceBase ( 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 386 of file DeviceBase.cpp.

◆ DeviceBase() [5/29]

dai::DeviceBase::DeviceBase ( 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 391 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 ( const Pipeline pipeline,
const DeviceInfo devInfo,
usb2Mode 
)
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() [7/29]

dai::DeviceBase::DeviceBase ( 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 396 of file DeviceBase.cpp.

◆ DeviceBase() [8/29]

dai::DeviceBase::DeviceBase ( 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 401 of file DeviceBase.cpp.

◆ DeviceBase() [9/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() [10/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version)
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() [11/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
usb2Mode 
)
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() [12/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
UsbSpeed  maxUsbSpeed 
)

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() [13/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
const dai::Path pathToCmd 
)

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() [14/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
const DeviceInfo devInfo 
)

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() [15/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
const DeviceInfo devInfo,
usb2Mode 
)
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() [16/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)

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() [17/29]

dai::DeviceBase::DeviceBase ( OpenVINO::Version  version,
const DeviceInfo devInfo,
const dai::Path pathToCmd 
)

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() [18/29]

dai::DeviceBase::DeviceBase ( Config  config)
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() [19/29]

dai::DeviceBase::DeviceBase ( Config  config,
const DeviceInfo devInfo 
)

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() [20/29]

dai::DeviceBase::DeviceBase ( const DeviceInfo devInfo)
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() [21/29]

dai::DeviceBase::DeviceBase ( const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)

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() [22/29]

dai::DeviceBase::DeviceBase ( std::string  nameOrDeviceId)

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() [23/29]

dai::DeviceBase::DeviceBase ( std::string  nameOrDeviceId,
UsbSpeed  maxUsbSpeed 
)

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.

◆ DeviceBase() [24/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( Config  config,
usb2Mode 
)
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() [25/29]

dai::DeviceBase::DeviceBase ( Config  config,
UsbSpeed  maxUsbSpeed 
)

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() [26/29]

dai::DeviceBase::DeviceBase ( Config  config,
const dai::Path pathToCmd 
)

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() [27/29]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBase::DeviceBase ( Config  config,
const DeviceInfo devInfo,
usb2Mode 
)
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() [28/29]

dai::DeviceBase::DeviceBase ( Config  config,
const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)

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() [29/29]

dai::DeviceBase::DeviceBase ( Config  config,
const DeviceInfo devInfo,
const dai::Path pathToCmd,
bool  dumpOnly = false 
)

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()

dai::DeviceBase::~DeviceBase ( )
virtual

Device destructor

Note
In the destructor of the derived class, remember to call close()

Definition at line 632 of file DeviceBase.cpp.

Member Function Documentation

◆ addLogCallback()

int dai::DeviceBase::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.

Parameters
callbackCallback to call whenever a log message arrives
Returns
Id which can be used to later remove the callback

Definition at line 1272 of file DeviceBase.cpp.

◆ close()

void dai::DeviceBase::close ( )

Explicitly closes connection to device.

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

Definition at line 516 of file DeviceBase.cpp.

◆ closeImpl()

void dai::DeviceBase::closeImpl ( )
protectedvirtual

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 in dai::Device.

Definition at line 536 of file DeviceBase.cpp.

◆ factoryResetCalibration()

void dai::DeviceBase::factoryResetCalibration ( )

Factory reset EEPROM data if factory backup is available.

Exceptions
std::runtime_exceptionIf factory reset was unsuccessful

Definition at line 1444 of file DeviceBase.cpp.

◆ flashCalibration()

bool dai::DeviceBase::flashCalibration ( CalibrationHandler  calibrationDataHandler)

Stores the Calibration and Device information to the Device EEPROM

Parameters
calibrationObjCalibrationHandler object which is loaded with calibration information.
Returns
true on successful flash, false on failure

Definition at line 1327 of file DeviceBase.cpp.

◆ flashCalibration2()

void dai::DeviceBase::flashCalibration2 ( CalibrationHandler  calibrationDataHandler)

Stores the Calibration and Device information to the Device EEPROM

Exceptions
std::runtime_exceptionif failed to flash the calibration
Parameters
calibrationObjCalibrationHandler object which is loaded with calibration information.

Definition at line 1336 of file DeviceBase.cpp.

◆ flashEepromClear()

void dai::DeviceBase::flashEepromClear ( )

Destructive action, deletes User area EEPROM contents Requires PROTECTED permissions

Exceptions
std::runtime_exceptionif failed to flash the calibration
Returns
True on successful flash, false on failure

Definition at line 1475 of file DeviceBase.cpp.

◆ flashFactoryCalibration()

void dai::DeviceBase::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

Exceptions
std::runtime_exceptionif failed to flash the calibration
Returns
True on successful flash, false on failure

Definition at line 1400 of file DeviceBase.cpp.

◆ flashFactoryEepromClear()

void dai::DeviceBase::flashFactoryEepromClear ( )

Destructive action, deletes Factory area EEPROM contents Requires FACTORY PROTECTED permissions

Exceptions
std::runtime_exceptionif failed to flash the calibration
Returns
True on successful flash, false on failure

Definition at line 1493 of file DeviceBase.cpp.

◆ getAllAvailableDevices()

std::vector< DeviceInfo > dai::DeviceBase::getAllAvailableDevices ( )
static

Returns all available devices

Returns
Vector of available devices

Definition at line 228 of file DeviceBase.cpp.

◆ getAllConnectedDevices()

std::vector< DeviceInfo > dai::DeviceBase::getAllConnectedDevices ( )
static

Returns information of all connected devices. The devices could be both connectable as well as already connected to devices.

Returns
Vector of connected device information

Definition at line 238 of file DeviceBase.cpp.

◆ getAnyAvailableDevice() [1/3]

std::tuple< bool, DeviceInfo > dai::DeviceBase::getAnyAvailableDevice ( )
static

Gets any available device

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

Definition at line 206 of file DeviceBase.cpp.

◆ getAnyAvailableDevice() [2/3]

std::tuple< bool, DeviceInfo > dai::DeviceBase::getAnyAvailableDevice ( std::chrono::milliseconds  timeout)
static

Waits for any available device with a timeout

Parameters
timeoutduration of time to wait for the any device
Returns
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

Definition at line 140 of file DeviceBase.cpp.

◆ getAnyAvailableDevice() [3/3]

std::tuple< bool, DeviceInfo > dai::DeviceBase::getAnyAvailableDevice ( std::chrono::milliseconds  timeout,
std::function< void()>  cb 
)
static

Waits for any available device with a timeout

Parameters
timeoutduration of time to wait for the any device
cbcallback function called between pooling intervals
Returns
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

Definition at line 144 of file DeviceBase.cpp.

◆ getAvailableStereoPairs()

std::vector< StereoPair > dai::DeviceBase::getAvailableStereoPairs ( )

Get stereo pairs taking into account the calibration and connected cameras.

Note
This method will always return a subset of getStereoPairs.
Returns
Vector of stereo pairs

Definition at line 1040 of file DeviceBase.cpp.

◆ getBootloaderVersion()

tl::optional< Version > dai::DeviceBase::getBootloaderVersion ( )

Gets Bootloader version if it was booted through Bootloader

Returns
DeviceBootloader::Version if booted through Bootloader or none otherwise

Definition at line 1188 of file DeviceBase.cpp.

◆ getCalibration()

CalibrationHandler dai::DeviceBase::getCalibration ( )

Retrieves the CalibrationHandler object containing the non-persistent calibration

Exceptions
std::runtime_exceptionif failed to get the calibration
Returns
The CalibrationHandler object containing the non-persistent calibration

Definition at line 1365 of file DeviceBase.cpp.

◆ getCameraSensorNames()

std::unordered_map< CameraBoardSocket, std::string > dai::DeviceBase::getCameraSensorNames ( )

Get sensor names for cameras that are connected to the device

Returns
Map/dictionary with camera sensor names, indexed by socket

Definition at line 1117 of file DeviceBase.cpp.

◆ getChipTemperature()

ChipTemperature dai::DeviceBase::getChipTemperature ( )

Retrieves current chip temperature as measured by device

Returns
Temperature of various onboard sensors

Definition at line 1172 of file DeviceBase.cpp.

◆ getCmxMemoryUsage()

MemoryInfo dai::DeviceBase::getCmxMemoryUsage ( )

Retrieves current CMX memory information from device

Returns
Used, remaining and total cmx memory

Definition at line 1160 of file DeviceBase.cpp.

◆ getConnectedCameraFeatures()

std::vector< CameraFeatures > dai::DeviceBase::getConnectedCameraFeatures ( )

Get cameras that are connected to the device with their features/properties

Returns
Vector of connected camera features

Definition at line 1109 of file DeviceBase.cpp.

◆ getConnectedCameras()

std::vector< CameraBoardSocket > dai::DeviceBase::getConnectedCameras ( )

Get cameras that are connected to the device

Returns
Vector of connected cameras

Definition at line 1036 of file DeviceBase.cpp.

◆ getConnectedIMU()

std::string dai::DeviceBase::getConnectedIMU ( )

Get connected IMU type

Returns
IMU type

Definition at line 1121 of file DeviceBase.cpp.

◆ getConnection() [1/2]

std::shared_ptr<XLinkConnection> dai::DeviceBase::getConnection ( )
inline

Returns underlying XLinkConnection

Definition at line 912 of file DeviceBase.hpp.

◆ getConnection() [2/2]

std::shared_ptr<const XLinkConnection> dai::DeviceBase::getConnection ( ) const
inline

Returns underlying XLinkConnection

Definition at line 919 of file DeviceBase.hpp.

◆ getConnectionInterfaces()

std::vector< ConnectionInterface > dai::DeviceBase::getConnectionInterfaces ( )

Get connection interfaces for device

Returns
Vector of connection type

Definition at line 1105 of file DeviceBase.cpp.

◆ getCrashDump()

dai::CrashDump dai::DeviceBase::getCrashDump ( bool  clearCrashDump = true)

Retrieves crash dump for debugging.

Definition at line 1260 of file DeviceBase.cpp.

◆ getDdrMemoryUsage()

MemoryInfo dai::DeviceBase::getDdrMemoryUsage ( )

Retrieves current DDR memory information from device

Returns
Used, remaining and total ddr memory

Definition at line 1156 of file DeviceBase.cpp.

◆ getDefaultSearchTime()

std::chrono::milliseconds dai::DeviceBase::getDefaultSearchTime ( )
static

Get the Default Search Time for finding devices.

Returns
Default search time in milliseconds

Definition at line 124 of file DeviceBase.cpp.

◆ getDeviceByMxId()

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

Finds a device by MX ID. Example: 14442C10D13EABCE00

Parameters
mxIdMyraidX ID which uniquely specifies a device
Returns
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device

Definition at line 243 of file DeviceBase.cpp.

◆ getDeviceInfo()

DeviceInfo dai::DeviceBase::getDeviceInfo ( ) const

Get the Device Info object o the device which is currently running

Returns
DeviceInfo of the current device in execution

Definition at line 1216 of file DeviceBase.cpp.

◆ getDeviceName()

std::string dai::DeviceBase::getDeviceName ( )

Get device name if available

Returns
device name or empty string if not available

Definition at line 1226 of file DeviceBase.cpp.

◆ getEmbeddedDeviceBinary() [1/2]

std::vector< std::uint8_t > dai::DeviceBase::getEmbeddedDeviceBinary ( bool  usb2Mode,
OpenVINO::Version  version = OpenVINO::VERSION_UNIVERSAL 
)
static

Gets device firmware binary for a specific OpenVINO version

Parameters
usb2ModeUSB2 mode firmware
versionVersion of OpenVINO which firmware will support
Returns
Firmware binary

Definition at line 255 of file DeviceBase.cpp.

◆ getEmbeddedDeviceBinary() [2/2]

std::vector< std::uint8_t > dai::DeviceBase::getEmbeddedDeviceBinary ( Config  config)
static

Gets device firmware binary for a specific configuration

Parameters
configFW with applied configuration
Returns
Firmware binary

Definition at line 259 of file DeviceBase.cpp.

◆ getEmbeddedIMUFirmwareVersion()

dai::Version dai::DeviceBase::getEmbeddedIMUFirmwareVersion ( )

Get embedded IMU firmware version to which IMU can be upgraded

Returns
Get embedded IMU firmware version to which IMU can be upgraded.

Definition at line 1136 of file DeviceBase.cpp.

◆ getFirstAvailableDevice()

std::tuple< bool, DeviceInfo > dai::DeviceBase::getFirstAvailableDevice ( bool  skipInvalidDevice = true)
static

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

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

Definition at line 213 of file DeviceBase.cpp.

◆ getGlobalProfilingData()

ProfilingData dai::DeviceBase::getGlobalProfilingData ( )
static

Get current global accumulated profiling data

Returns
ProfilingData from all devices

Definition at line 263 of file DeviceBase.cpp.

◆ getIMUFirmwareUpdateStatus()

std::tuple< bool, unsigned int > dai::DeviceBase::getIMUFirmwareUpdateStatus ( )

Get IMU firmware update status

Returns
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

Definition at line 1151 of file DeviceBase.cpp.

◆ getIMUFirmwareVersion()

dai::Version dai::DeviceBase::getIMUFirmwareVersion ( )

Get connected IMU firmware version

Returns
IMU firmware version

Definition at line 1125 of file DeviceBase.cpp.

◆ getIrDrivers()

std::vector< std::tuple< std::string, int, int > > dai::DeviceBase::getIrDrivers ( )

Retrieves detected IR laser/LED drivers.

Returns
Vector of tuples containing: driver name, I2C bus, I2C address. For OAK-D-Pro it should be [{"LM3644", 2, 0x63}]

Definition at line 1256 of file DeviceBase.cpp.

◆ getLeonCssCpuUsage()

CpuUsage dai::DeviceBase::getLeonCssCpuUsage ( )

Retrieves average CSS Leon CPU usage

Returns
Average CPU usage and sampling duration

Definition at line 1176 of file DeviceBase.cpp.

◆ getLeonCssHeapUsage()

MemoryInfo dai::DeviceBase::getLeonCssHeapUsage ( )

Retrieves current CSS Leon CPU heap information from device

Returns
Used, remaining and total heap memory

Definition at line 1164 of file DeviceBase.cpp.

◆ getLeonMssCpuUsage()

CpuUsage dai::DeviceBase::getLeonMssCpuUsage ( )

Retrieves average MSS Leon CPU usage

Returns
Average CPU usage and sampling duration

Definition at line 1180 of file DeviceBase.cpp.

◆ getLeonMssHeapUsage()

MemoryInfo dai::DeviceBase::getLeonMssHeapUsage ( )

Retrieves current MSS Leon CPU heap information from device

Returns
Used, remaining and total heap memory

Definition at line 1168 of file DeviceBase.cpp.

◆ getLogLevel()

LogLevel dai::DeviceBase::getLogLevel ( )

Gets current logging severity level of the device.

Returns
Logging severity level

Definition at line 1200 of file DeviceBase.cpp.

◆ getLogOutputLevel()

LogLevel dai::DeviceBase::getLogOutputLevel ( )

Gets logging level which decides printing level to standard output.

Returns
Standard output printing severity

Definition at line 1236 of file DeviceBase.cpp.

◆ getMxId()

std::string dai::DeviceBase::getMxId ( )

Get MxId of device

Returns
MxId of connected device

Definition at line 1032 of file DeviceBase.cpp.

◆ getProductName()

std::string dai::DeviceBase::getProductName ( )

Get product name if available

Returns
product name or empty string if not available

Definition at line 1220 of file DeviceBase.cpp.

◆ getProfilingData()

ProfilingData dai::DeviceBase::getProfilingData ( )

Get current accumulated profiling data

Returns
ProfilingData from the specific device

Definition at line 1268 of file DeviceBase.cpp.

◆ getStereoPairs()

std::vector< StereoPair > dai::DeviceBase::getStereoPairs ( )

Get stereo pairs based on the device type.

Returns
Vector of stereo pairs

Definition at line 1113 of file DeviceBase.cpp.

◆ getSystemInformationLoggingRate()

float dai::DeviceBase::getSystemInformationLoggingRate ( )

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

Returns
Logging rate in Hz

Definition at line 1319 of file DeviceBase.cpp.

◆ getUsbSpeed()

UsbSpeed dai::DeviceBase::getUsbSpeed ( )

Retrieves USB connection speed

Returns
USB connection speed of connected device if applicable. Unknown otherwise.

Definition at line 1184 of file DeviceBase.cpp.

◆ getXLinkChunkSize()

int dai::DeviceBase::getXLinkChunkSize ( )

Gets current XLink chunk size.

Returns
XLink chunk size in bytes

Definition at line 1208 of file DeviceBase.cpp.

◆ hasCrashDump()

bool dai::DeviceBase::hasCrashDump ( )

Retrieves whether the is crash dump stored on device or not.

Definition at line 1264 of file DeviceBase.cpp.

◆ init() [1/17]

void dai::DeviceBase::init ( Config  config,
const dai::Path pathToCmd 
)
protected

Definition at line 492 of file DeviceBase.cpp.

◆ init() [2/17]

void dai::DeviceBase::init ( Config  config,
const DeviceInfo devInfo,
const dai::Path pathToCmd 
)
protected

Definition at line 502 of file DeviceBase.cpp.

◆ init() [3/17]

void dai::DeviceBase::init ( Config  config,
const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)
protected

Definition at line 497 of file DeviceBase.cpp.

◆ init() [4/17]

void dai::DeviceBase::init ( Config  config,
UsbSpeed  maxUsbSpeed 
)
protected

Definition at line 487 of file DeviceBase.cpp.

◆ init() [5/17]

void dai::DeviceBase::init ( Config  config,
UsbSpeed  maxUsbSpeed,
const dai::Path pathToMvcmd 
)
protected

Definition at line 663 of file DeviceBase.cpp.

◆ init() [6/17]

void dai::DeviceBase::init ( const Pipeline pipeline)
protected

Definition at line 445 of file DeviceBase.cpp.

◆ init() [7/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
const dai::Path pathToCmd 
)
protected

Definition at line 458 of file DeviceBase.cpp.

◆ init() [8/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
const DeviceInfo devInfo 
)
protected

Definition at line 466 of file DeviceBase.cpp.

◆ init() [9/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
const DeviceInfo devInfo,
bool  usb2Mode 
)
protected

◆ init() [10/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
const DeviceInfo devInfo,
const dai::Path pathToCmd 
)
protected

Definition at line 479 of file DeviceBase.cpp.

◆ init() [11/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
const DeviceInfo devInfo,
UsbSpeed  maxUsbSpeed 
)
protected

Definition at line 474 of file DeviceBase.cpp.

◆ init() [12/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
UsbSpeed  maxUsbSpeed 
)
protected

Definition at line 453 of file DeviceBase.cpp.

◆ init() [13/17]

void dai::DeviceBase::init ( const Pipeline pipeline,
UsbSpeed  maxUsbSpeed,
const dai::Path pathToMvcmd 
)
protected

Definition at line 657 of file DeviceBase.cpp.

◆ init() [14/17]

void dai::DeviceBase::init ( OpenVINO::Version  version)
protected

Definition at line 422 of file DeviceBase.cpp.

◆ init() [15/17]

void dai::DeviceBase::init ( OpenVINO::Version  version,
const dai::Path pathToCmd 
)
protected

Definition at line 431 of file DeviceBase.cpp.

◆ init() [16/17]

void dai::DeviceBase::init ( OpenVINO::Version  version,
UsbSpeed  maxUsbSpeed 
)
protected

Definition at line 440 of file DeviceBase.cpp.

◆ init() [17/17]

void dai::DeviceBase::init ( OpenVINO::Version  version,
UsbSpeed  maxUsbSpeed,
const dai::Path pathToMvcmd 
)
protected

Definition at line 649 of file DeviceBase.cpp.

◆ init2()

void dai::DeviceBase::init2 ( Config  cfg,
const dai::Path pathToMvcmd,
tl::optional< const Pipeline & >  pipeline 
)
private

Definition at line 670 of file DeviceBase.cpp.

◆ isClosed()

bool dai::DeviceBase::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.

Definition at line 627 of file DeviceBase.cpp.

◆ isEepromAvailable()

bool dai::DeviceBase::isEepromAvailable ( )

Check if EEPROM is available

Returns
True if EEPROM is present on board, false otherwise

Definition at line 1323 of file DeviceBase.cpp.

◆ isPipelineRunning()

bool dai::DeviceBase::isPipelineRunning ( )

Checks if devices pipeline is already running

Returns
True if running, false otherwise

Definition at line 1192 of file DeviceBase.cpp.

◆ readCalibration()

CalibrationHandler dai::DeviceBase::readCalibration ( )

Fetches the EEPROM data from the device and loads it into CalibrationHandler object If no calibration is flashed, it returns default

Returns
The CalibrationHandler object containing the calibration currently flashed on device EEPROM

Definition at line 1376 of file DeviceBase.cpp.

◆ readCalibration2()

CalibrationHandler dai::DeviceBase::readCalibration2 ( )

Fetches the EEPROM data from the device and loads it into CalibrationHandler object

Exceptions
std::runtime_exceptionif no calibration is flashed
Returns
The CalibrationHandler object containing the calibration currently flashed on device EEPROM

Definition at line 1385 of file DeviceBase.cpp.

◆ readCalibrationOrDefault()

CalibrationHandler dai::DeviceBase::readCalibrationOrDefault ( )

Fetches the EEPROM data from the device and loads it into CalibrationHandler object If no calibration is flashed, it returns default

Returns
The CalibrationHandler object containing the calibration currently flashed on device EEPROM

Definition at line 1396 of file DeviceBase.cpp.

◆ readCalibrationRaw()

std::vector< std::uint8_t > dai::DeviceBase::readCalibrationRaw ( )

Fetches the raw EEPROM data from User area

Exceptions
std::runtime_exceptionif any error occurred
Returns
Binary dump of User area EEPROM data

Definition at line 1453 of file DeviceBase.cpp.

◆ readFactoryCalibration()

CalibrationHandler dai::DeviceBase::readFactoryCalibration ( )

Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object

Exceptions
std::runtime_exceptionif no calibration is flashed
Returns
The CalibrationHandler object containing the calibration currently flashed on device EEPROM in Factory Area

Definition at line 1424 of file DeviceBase.cpp.

◆ readFactoryCalibrationOrDefault()

CalibrationHandler dai::DeviceBase::readFactoryCalibrationOrDefault ( )

Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object If no calibration is flashed, it returns default

Returns
The CalibrationHandler object containing the calibration currently flashed on device EEPROM in Factory Area

Definition at line 1434 of file DeviceBase.cpp.

◆ readFactoryCalibrationRaw()

std::vector< std::uint8_t > dai::DeviceBase::readFactoryCalibrationRaw ( )

Fetches the raw EEPROM data from Factory area

Exceptions
std::runtime_exceptionif any error occurred
Returns
Binary dump of Factory area EEPROM data

Definition at line 1464 of file DeviceBase.cpp.

◆ removeLogCallback()

bool dai::DeviceBase::removeLogCallback ( int  callbackId)

Removes a callback

Parameters
callbackIdId of callback to be removed
Returns
True if callback was removed, false otherwise

Definition at line 1286 of file DeviceBase.cpp.

◆ setCalibration()

void dai::DeviceBase::setCalibration ( CalibrationHandler  calibrationDataHandler)

Sets the Calibration at runtime. This is not persistent and will be lost after device reset.

Exceptions
std::runtime_exceptionif failed to set the calibration
Parameters
calibrationObjCalibrationHandler object which is loaded with calibration information.

Definition at line 1356 of file DeviceBase.cpp.

◆ setIrFloodLightBrightness()

bool dai::DeviceBase::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

Parameters
mACurrent in mA that will determine brightness, 0 or negative to turn off
maskOptional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
Returns
True on success, false if not found or other failure

Definition at line 1248 of file DeviceBase.cpp.

◆ setIrFloodLightIntensity()

bool dai::DeviceBase::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

Parameters
intensityIntensity on range 0 to 1, that will determine brightness, 0 or negative to turn off
maskOptional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
Returns
True on success, false if not found or other failure

Definition at line 1252 of file DeviceBase.cpp.

◆ setIrLaserDotProjectorBrightness()

bool dai::DeviceBase::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

Parameters
mACurrent in mA that will determine brightness, 0 or negative to turn off
maskOptional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
Returns
True on success, false if not found or other failure

Definition at line 1240 of file DeviceBase.cpp.

◆ setIrLaserDotProjectorIntensity()

bool dai::DeviceBase::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

Parameters
intensityIntensity on range 0 to 1, that will determine brightness. 0 or negative to turn off
maskOptional mask to modify only Left (0x1) or Right (0x2) sides on OAK-D-Pro-W-DEV
Returns
True on success, false if not found or other failure

Definition at line 1244 of file DeviceBase.cpp.

◆ setLogLevel()

void dai::DeviceBase::setLogLevel ( LogLevel  level)

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

Parameters
levelLogging severity

Definition at line 1196 of file DeviceBase.cpp.

◆ setLogOutputLevel()

void dai::DeviceBase::setLogOutputLevel ( LogLevel  level)

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

Parameters
levelStandard output printing severity

Definition at line 1232 of file DeviceBase.cpp.

◆ setSystemInformationLoggingRate()

void dai::DeviceBase::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
rateHzLogging rate in Hz

Definition at line 1315 of file DeviceBase.cpp.

◆ setTimesync() [1/2]

void dai::DeviceBase::setTimesync ( bool  enable)

Enables or disables Timesync service on device. It keeps host and device clocks in sync.

Parameters
enableEnables or disables consistent timesyncing

Definition at line 1307 of file DeviceBase.cpp.

◆ setTimesync() [2/2]

void dai::DeviceBase::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
periodInterval between timesync runs
numSamplesNumber of timesync samples per run which are used to compute a better value. Set to zero to disable timesync
randomIf true partial timesync requests will be performed at random intervals, otherwise at fixed intervals

Definition at line 1298 of file DeviceBase.cpp.

◆ setXLinkChunkSize()

void dai::DeviceBase::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
sizeBytesXLink chunk size in bytes

Definition at line 1204 of file DeviceBase.cpp.

◆ setXLinkRateLimit()

void dai::DeviceBase::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
maxRateBytesPerSecondRate limit in Bytes/second
burstSizeSize in Bytes for how much to attempt to send once, 0 = auto
waitUsTime in microseconds to wait for replenishing tokens, 0 = auto

Definition at line 1212 of file DeviceBase.cpp.

◆ startIMUFirmwareUpdate()

bool dai::DeviceBase::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.

Parameters
forceUpdateForce firmware update or not. Will perform FW update regardless of current version and embedded firmware version.
Returns
Returns whether firmware update can be started. Returns false if IMU node is started.

Definition at line 1147 of file DeviceBase.cpp.

◆ startPipeline() [1/2]

bool dai::DeviceBase::startPipeline ( )

Starts the execution of the devices pipeline

Returns
True if pipeline started, false otherwise

Definition at line 1511 of file DeviceBase.cpp.

◆ startPipeline() [2/2]

bool dai::DeviceBase::startPipeline ( const Pipeline pipeline)

Starts the execution of a given pipeline

Parameters
pipelineOpenVINO version of the pipeline must match the one which the device was booted with.
Returns
True if pipeline started, false otherwise

Definition at line 1516 of file DeviceBase.cpp.

◆ startPipelineImpl()

bool dai::DeviceBase::startPipelineImpl ( const Pipeline pipeline)
protectedvirtual

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 in dai::Device.

Definition at line 1525 of file DeviceBase.cpp.

◆ tryGetDevice()

void dai::DeviceBase::tryGetDevice ( )
private

Definition at line 320 of file DeviceBase.cpp.

◆ tryStartPipeline()

void dai::DeviceBase::tryStartPipeline ( const Pipeline pipeline)
protected

a safe way to start a pipeline, which is closed if any exception occurs

Definition at line 636 of file DeviceBase.cpp.

Member Data Documentation

◆ bootloaderVersion

tl::optional<Version> dai::DeviceBase::bootloaderVersion
private

Definition at line 975 of file DeviceBase.hpp.

◆ closed

bool dai::DeviceBase::closed {false}
private

Definition at line 1005 of file DeviceBase.hpp.

◆ closedMtx

std::mutex dai::DeviceBase::closedMtx
mutableprivate

Definition at line 1004 of file DeviceBase.hpp.

◆ config

Config dai::DeviceBase::config
private

Definition at line 1012 of file DeviceBase.hpp.

◆ connection

std::shared_ptr<XLinkConnection> dai::DeviceBase::connection
protected

Definition at line 924 of file DeviceBase.hpp.

◆ DEFAULT_SEARCH_TIME

constexpr std::chrono::seconds dai::DeviceBase::DEFAULT_SEARCH_TIME {3}
staticconstexpr

Default search time for constructors which discover devices.

Definition at line 55 of file DeviceBase.hpp.

◆ DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ

constexpr float dai::DeviceBase::DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ {1.0f}
staticconstexpr

Default rate at which system information is logged.

Definition at line 57 of file DeviceBase.hpp.

◆ DEFAULT_TIMESYNC_NUM_SAMPLES

constexpr int dai::DeviceBase::DEFAULT_TIMESYNC_NUM_SAMPLES {10}
staticconstexpr

Default Timesync number of samples per sync.

Definition at line 63 of file DeviceBase.hpp.

◆ DEFAULT_TIMESYNC_PERIOD

constexpr std::chrono::milliseconds dai::DeviceBase::DEFAULT_TIMESYNC_PERIOD {5000}
staticconstexpr

Default Timesync period.

Definition at line 61 of file DeviceBase.hpp.

◆ DEFAULT_TIMESYNC_RANDOM

constexpr bool dai::DeviceBase::DEFAULT_TIMESYNC_RANDOM {true}
staticconstexpr

Default Timesync packet interval randomness.

Definition at line 65 of file DeviceBase.hpp.

◆ DEFAULT_USB_SPEED

constexpr UsbSpeed dai::DeviceBase::DEFAULT_USB_SPEED {UsbSpeed::SUPER}
staticconstexpr

Default UsbSpeed for device connection.

Definition at line 59 of file DeviceBase.hpp.

◆ deviceInfo

DeviceInfo dai::DeviceBase::deviceInfo = {}
private

Definition at line 974 of file DeviceBase.hpp.

◆ dumpOnly

bool dai::DeviceBase::dumpOnly = false
private

Definition at line 1015 of file DeviceBase.hpp.

◆ firmwarePath

dai::Path dai::DeviceBase::firmwarePath
private

Definition at line 1014 of file DeviceBase.hpp.

◆ lastWatchdogPingTime

std::chrono::steady_clock::time_point dai::DeviceBase::lastWatchdogPingTime
private

Definition at line 1001 of file DeviceBase.hpp.

◆ lastWatchdogPingTimeMtx

std::mutex dai::DeviceBase::lastWatchdogPingTimeMtx
private

Definition at line 1000 of file DeviceBase.hpp.

◆ logCallbackMap

std::unordered_map<int, std::function<void(LogMessage)> > dai::DeviceBase::logCallbackMap
private

Definition at line 980 of file DeviceBase.hpp.

◆ logCallbackMapMtx

std::mutex dai::DeviceBase::logCallbackMapMtx
private

Definition at line 979 of file DeviceBase.hpp.

◆ loggingRunning

std::atomic<bool> dai::DeviceBase::loggingRunning {true}
private

Definition at line 992 of file DeviceBase.hpp.

◆ loggingThread

std::thread dai::DeviceBase::loggingThread
private

Definition at line 991 of file DeviceBase.hpp.

◆ monitorThread

std::thread dai::DeviceBase::monitorThread
private

Definition at line 999 of file DeviceBase.hpp.

◆ pimpl

Pimpl<Impl> dai::DeviceBase::pimpl
private

Definition at line 1008 of file DeviceBase.hpp.

◆ pipelineSchema

tl::optional<PipelineSchema> dai::DeviceBase::pipelineSchema
private

Definition at line 1018 of file DeviceBase.hpp.

◆ profilingRunning

std::atomic<bool> dai::DeviceBase::profilingRunning {true}
private

Definition at line 996 of file DeviceBase.hpp.

◆ profilingThread

std::thread dai::DeviceBase::profilingThread
private

Definition at line 995 of file DeviceBase.hpp.

◆ timesyncRunning

std::atomic<bool> dai::DeviceBase::timesyncRunning {true}
private

Definition at line 988 of file DeviceBase.hpp.

◆ timesyncThread

std::thread dai::DeviceBase::timesyncThread
private

Definition at line 987 of file DeviceBase.hpp.

◆ uniqueCallbackId

int dai::DeviceBase::uniqueCallbackId = 0
private

Definition at line 978 of file DeviceBase.hpp.

◆ watchdogRunning

std::atomic<bool> dai::DeviceBase::watchdogRunning {true}
private

Definition at line 984 of file DeviceBase.hpp.

◆ watchdogThread

std::thread dai::DeviceBase::watchdogThread
private

Definition at line 983 of file DeviceBase.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