Class DeviceBase
Defined in File DeviceBase.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Derived Type
public dai::Device(Class Device)
Class Documentation
-
class DeviceBase
The core of depthai device for RAII, connects to device and maintains watchdog, timesync, …
Subclassed by dai::Device
Public Types
Public Functions
-
DeviceBase()
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
-
DeviceBase(UsbSpeed maxUsbSpeed)
Connects to device
- Parameters:
maxUsbSpeed – Maximum allowed USB speed
-
DeviceBase(const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
Connects to device specified by devInfo.
- Parameters:
devInfo – DeviceInfo which specifies which device to connect to
maxUsbSpeed – Maximum allowed USB speed
-
DeviceBase(const DeviceInfo &devInfo, const std::filesystem::path &pathToCmd)
Connects to device specified by devInfo.
- Parameters:
devInfo – DeviceInfo which specifies which device to connect to
pathToCmd – Path to custom device firmware
-
explicit DeviceBase(Config config)
Connects to any available device with custom config.
- Parameters:
config – Device custom configuration to boot with
-
DeviceBase(Config config, const DeviceInfo &devInfo)
Connects to device ‘devInfo’ with custom config.
- Parameters:
config – Device custom configuration to boot with
devInfo – DeviceInfo which specifies which device to connect to
-
explicit DeviceBase(const DeviceInfo &devInfo)
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters:
devInfo – DeviceInfo which specifies which device to connect to
-
DeviceBase(std::string nameOrDeviceId)
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters:
nameOrDeviceId – Creates DeviceInfo with nameOrDeviceId to connect to
-
DeviceBase(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed)
Connects to any available device with a DEFAULT_SEARCH_TIME timeout. Uses OpenVINO version OpenVINO::VERSION_UNIVERSAL
- Parameters:
nameOrDeviceId – Creates DeviceInfo with nameOrDeviceId to connect to
maxUsbSpeed – Maximum allowed USB speed
-
DeviceBase(Config config, UsbSpeed maxUsbSpeed)
Connects to device specified by devInfo.
- Parameters:
config – Config with which the device will be booted with
maxUsbSpeed – Maximum allowed USB speed
-
DeviceBase(Config config, const std::filesystem::path &pathToCmd)
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
- Parameters:
config – Config with which the device will be booted with
pathToCmd – Path to custom device firmware
-
DeviceBase(Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
Connects to device specified by devInfo.
- Parameters:
config – Config with which the device will be booted with
devInfo – DeviceInfo which specifies which device to connect to
maxUsbSpeed – Maximum allowed USB speed
-
DeviceBase(Config config, const DeviceInfo &devInfo, const std::filesystem::path &pathToCmd, bool dumpOnly = false)
Connects to device specified by devInfo.
- Parameters:
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
-
virtual ~DeviceBase()
Device destructor
Note
In the destructor of the derived class, remember to call close()
-
std::optional<Version> getBootloaderVersion()
Gets Bootloader version if it was booted through Bootloader
- Returns:
DeviceBootloader::Version if booted through Bootloader or none otherwise
-
bool isPipelineRunning()
Checks if devices pipeline is already running
- Returns:
True if running, false otherwise
-
bool startPipeline(const Pipeline &pipeline)
Starts the execution of a given pipeline
- Parameters:
pipeline – OpenVINO version of the pipeline must match the one which the device was booted with.
- Returns:
True if pipeline started, false otherwise
-
void setLogLevel(LogLevel level)
Sets the devices logging severity level. This level affects which logs are transferred from device to host.
- Parameters:
level – Logging severity
-
void setNodeLogLevel(int64_t id, LogLevel level)
Sets the logging severity level for a specific node with a given ID.
- Parameters:
id – Node ID
level – Logging severity
-
LogLevel getLogLevel()
Gets current logging severity level of the device.
- Returns:
Logging severity level
-
LogLevel getNodeLogLevel(int64_t id)
Gets the logging severity level for a specific node with a given ID.
- Parameters:
id – Node ID
- Returns:
Logging severity level
-
void setXLinkChunkSize(int sizeBytes)
Sets the chunk size for splitting device-sent XLink packets. A larger value could increase performance, and 0 disables chunking. A negative value is ignored. Device defaults are configured per protocol, currently 64*1024 for both USB and Ethernet.
- Parameters:
sizeBytes – XLink chunk size in bytes
-
int getXLinkChunkSize()
Gets current XLink chunk size.
- Returns:
XLink chunk size in bytes
-
DeviceInfo getDeviceInfo() const
Get the Device Info object o the device which is currently running
- Returns:
DeviceInfo of the current device in execution
-
std::string getDeviceName()
Get device name if available
- Returns:
device name or empty string if not available
-
std::string getProductName()
Get product name if available
- Returns:
product name or empty string if not available
-
std::string getMxId()
Get MxId of device
- Returns:
MxId of connected device
-
std::string getDeviceId()
Get DeviceId of device
- Returns:
DeviceId of connected device
-
void setLogOutputLevel(LogLevel level)
Sets logging level which decides printing level to standard output. If lower than setLogLevel, no messages will be printed
- Parameters:
level – Standard output printing severity
-
LogLevel getLogOutputLevel()
Gets logging level which decides printing level to standard output.
- Returns:
Standard output printing severity
-
bool setIrLaserDotProjectorIntensity(float intensity, int mask = -1)
Sets the intensity of the IR Laser Dot Projector. Limits: up to 765mA at 30% frame time duty cycle when exposure time is longer than 30% frame time. Otherwise, duty cycle is 100% of exposure time, with current increased up to max 1200mA to make up for shorter duty cycle. The duty cycle is controlled by
leftcamera STROBE, aligned to start of exposure. The emitter is turned off by default- Parameters:
intensity – Intensity on range 0 to 1, that will determine brightness. 0 or negative to turn off
mask – Optional 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
-
bool setIrFloodLightIntensity(float intensity, int mask = -1)
Sets the intensity of the IR Flood Light. Limits: Intensity is directly normalized to 0 - 1500mA current. The duty cycle is 30% when exposure time is longer than 30% frame time. Otherwise, duty cycle is 100% of exposure time. The duty cycle is controlled by the
leftcamera STROBE, aligned to start of exposure. The emitter is turned off by default- Parameters:
intensity – Intensity on range 0 to 1, that will determine brightness, 0 or negative to turn off
mask – Optional 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
-
std::vector<std::tuple<std::string, int, int>> 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}]
-
bool hasCrashDump()
Retrieves whether the is crash dump stored on device or not.
-
ProfilingData getProfilingData()
Get current accumulated profiling data
- Returns:
ProfilingData from the specific device
-
int addLogCallback(std::function<void(LogMessage)> callback)
Add a callback for device logging. The callback will be called from a separate thread with the LogMessage being passed.
- Parameters:
callback – Callback to call whenever a log message arrives
- Returns:
Id which can be used to later remove the callback
-
bool removeLogCallback(int callbackId)
Removes a callback
- Parameters:
callbackId – Id of callback to be removed
- Returns:
True if callback was removed, false otherwise
-
void setSystemInformationLoggingRate(float rateHz)
Sets rate of system information logging (“info” severity). Default 1Hz If parameter is less or equal to zero, then system information logging will be disabled
- Parameters:
rateHz – Logging rate in Hz
-
float getSystemInformationLoggingRate()
Gets current rate of system information logging (“info” severity) in Hz.
- Returns:
Logging rate in Hz
-
std::vector<CameraBoardSocket> getConnectedCameras()
Get cameras that are connected to the device
- Returns:
Vector of connected cameras
-
std::vector<ConnectionInterface> getConnectionInterfaces()
Get connection interfaces for device
- Returns:
Vector of connection type
-
std::vector<CameraFeatures> getConnectedCameraFeatures()
Get cameras that are connected to the device with their features/properties
- Returns:
Vector of connected camera features
-
std::vector<StereoPair> getStereoPairs()
Get stereo pairs based on the device type.
- Returns:
Vector of stereo pairs
-
std::vector<StereoPair> getAvailableStereoPairs()
Get stereo pairs taking into account the calibration and connected cameras.
Note
This method will always return a subset of
getStereoPairs.- Returns:
Vector of stereo pairs
-
std::unordered_map<CameraBoardSocket, std::string> getCameraSensorNames()
Get sensor names for cameras that are connected to the device
- Returns:
Map/dictionary with camera sensor names, indexed by socket
-
std::string getConnectedIMU()
Get connected IMU type
- Returns:
IMU type
-
dai::Version getIMUFirmwareVersion()
Get connected IMU firmware version
- Returns:
IMU firmware version
-
dai::Version getEmbeddedIMUFirmwareVersion()
Get embedded IMU firmware version to which IMU can be upgraded
- Returns:
Get embedded IMU firmware version to which IMU can be upgraded.
-
bool startIMUFirmwareUpdate(bool forceUpdate = false)
Starts IMU firmware update asynchronously only if IMU node is not running. If current firmware version is the same as embedded firmware version then it’s no-op. Can be overridden by forceUpdate parameter. State of firmware update can be monitored using getIMUFirmwareUpdateStatus API.
- Parameters:
forceUpdate – Force 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.
-
std::tuple<bool, float> 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
-
MemoryInfo getDdrMemoryUsage()
Retrieves current DDR memory information from device
- Returns:
Used, remaining and total ddr memory
-
MemoryInfo getCmxMemoryUsage()
Retrieves current CMX memory information from device
- Returns:
Used, remaining and total cmx memory
-
MemoryInfo getLeonCssHeapUsage()
Retrieves current CSS Leon CPU heap information from device
- Returns:
Used, remaining and total heap memory
-
MemoryInfo getLeonMssHeapUsage()
Retrieves current MSS Leon CPU heap information from device
- Returns:
Used, remaining and total heap memory
-
ChipTemperature getChipTemperature()
Retrieves current chip temperature as measured by device
- Returns:
Temperature of various onboard sensors
-
CpuUsage getLeonCssCpuUsage()
Retrieves average CSS Leon CPU usage
- Returns:
Average CPU usage and sampling duration
-
CpuUsage getLeonMssCpuUsage()
Retrieves average MSS Leon CPU usage
- Returns:
Average CPU usage and sampling duration
-
int64_t getProcessMemoryUsage()
Retrieves current Rss memory usage of the device process
- Returns:
Current Rss memory used
-
bool isEepromAvailable()
Check if EEPROM is available
- Returns:
True if EEPROM is present on board, false otherwise
-
bool tryFlashCalibration(CalibrationHandler calibrationDataHandler)
Stores the Calibration and Device information to the Device EEPROM
- Parameters:
calibrationObj – CalibrationHandler object which is loaded with calibration information.
- Returns:
true on successful flash, false on failure
-
void flashCalibration(CalibrationHandler calibrationDataHandler)
Stores the Calibration and Device information to the Device EEPROM
- Throws:
std::runtime_exception – if failed to flash the calibration
- Parameters:
calibrationObj – CalibrationHandler object which is loaded with calibration information.
-
void setCalibration(CalibrationHandler calibrationDataHandler)
Sets the Calibration at runtime. This is not persistent and will be lost after device reset.
- Throws:
std::runtime_error – if failed to set the calibration
- Parameters:
calibrationObj – CalibrationHandler object which is loaded with calibration information.
-
CalibrationHandler getCalibration()
Retrieves the CalibrationHandler object containing the non-persistent calibration
- Throws:
std::runtime_exception – if failed to get the calibration
- Returns:
The CalibrationHandler object containing the non-persistent calibration
-
CalibrationHandler 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
-
CalibrationHandler readCalibration2()
Fetches the EEPROM data from the device and loads it into CalibrationHandler object
- Throws:
std::runtime_exception – if no calibration is flashed
- Returns:
The CalibrationHandler object containing the calibration currently flashed on device EEPROM
-
CalibrationHandler 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
-
void factoryResetCalibration()
Factory reset EEPROM data if factory backup is available.
- Throws:
std::runtime_exception – If factory reset was unsuccessful
-
void flashFactoryCalibration(CalibrationHandler calibrationHandler)
Stores the Calibration and Device information to the Device EEPROM in Factory area To perform this action, correct env variable must be set
- Throws:
std::runtime_exception – if failed to flash the calibration
- Returns:
True on successful flash, false on failure
-
void flashEepromClear()
Destructive action, deletes User area EEPROM contents Requires PROTECTED permissions
- Throws:
std::runtime_exception – if failed to flash the calibration
- Returns:
True on successful flash, false on failure
-
void flashFactoryEepromClear()
Destructive action, deletes Factory area EEPROM contents Requires FACTORY PROTECTED permissions
- Throws:
std::runtime_exception – if failed to flash the calibration
- Returns:
True on successful flash, false on failure
-
CalibrationHandler readFactoryCalibration()
Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object
- Throws:
std::runtime_exception – if no calibration is flashed
- Returns:
The CalibrationHandler object containing the calibration currently flashed on device EEPROM in Factory Area
-
CalibrationHandler 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
-
std::vector<std::uint8_t> readCalibrationRaw()
Fetches the raw EEPROM data from User area
- Throws:
std::runtime_exception – if any error occurred
- Returns:
Binary dump of User area EEPROM data
-
std::vector<std::uint8_t> readFactoryCalibrationRaw()
Fetches the raw EEPROM data from Factory area
- Throws:
std::runtime_exception – if any error occurred
- Returns:
Binary dump of Factory area EEPROM data
-
UsbSpeed getUsbSpeed()
Retrieves USB connection speed
- Returns:
USB connection speed of connected device if applicable. Unknown otherwise.
-
void setTimesync(std::chrono::milliseconds period, int numSamples, bool random)
Configures Timesync service on device. It keeps host and device clocks in sync First time timesync is started it waits until the initial sync is completed Afterwards the function changes the following parameters
- Parameters:
period – Interval between timesync runs
numSamples – Number of timesync samples per run which are used to compute a better value. Set to zero to disable timesync
random – If true partial timesync requests will be performed at random intervals, otherwise at fixed intervals
-
void setTimesync(bool enable)
Enables or disables Timesync service on device. It keeps host and device clocks in sync.
- Parameters:
enable – Enables or disables consistent timesyncing
-
void close()
Explicitly closes connection to device.
Note
This function does not need to be explicitly called as destructor closes the device automatically
-
bool isClosed() const
Is the device already closed (or disconnected)
Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.
-
void crashDevice()
Crashes the device
Warning
ONLY FOR TESTING PURPOSES, it causes an unrecoverable crash on the device
-
inline std::shared_ptr<XLinkConnection> getConnection()
Returns underlying XLinkConnection
-
inline std::shared_ptr<const XLinkConnection> getConnection() const
Returns underlying XLinkConnection
-
void setMaxReconnectionAttempts(int maxAttempts, std::function<void(ReconnectionStatus)> callBack = nullptr)
Sets max number of automatic reconnection attempts
- Parameters:
maxAttempts – Maximum number of reconnection attempts, 0 to disable reconnection
callBack – Callback to be called when reconnection is attempted
Public Static Functions
-
static std::chrono::milliseconds getDefaultSearchTime()
Get the Default Search Time for finding devices.
- Returns:
Default search time in milliseconds
-
static std::tuple<bool, DeviceInfo> getAnyAvailableDevice(std::chrono::milliseconds timeout)
Waits for any available device with a timeout
- Parameters:
timeout – duration 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
-
static std::tuple<bool, DeviceInfo> getAnyAvailableDevice()
Gets any available device
- Returns:
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device
-
static std::tuple<bool, DeviceInfo> getAnyAvailableDevice(std::chrono::milliseconds timeout, std::function<void()> cb)
Waits for any available device with a timeout
- Parameters:
timeout – duration of time to wait for the any device
cb – callback function called between pooling intervals
- Returns:
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device
-
static std::tuple<bool, DeviceInfo> getFirstAvailableDevice(bool skipInvalidDevice = true)
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
-
static std::tuple<bool, DeviceInfo> getDeviceById(std::string deviceId)
Finds a device by Device ID. Example: 14442C10D13EABCE00
- Parameters:
deviceId – Device ID which uniquely specifies a device
- Returns:
Tuple of bool and DeviceInfo. Bool specifies if device was found. DeviceInfo specifies the found device
-
static std::vector<DeviceInfo> getAllAvailableDevices()
Returns all available devices
- Returns:
Vector of available devices
-
static std::vector<DeviceInfo> getAllConnectedDevices()
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
-
static std::vector<std::uint8_t> getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version = OpenVINO::VERSION_UNIVERSAL)
Gets device firmware binary for a specific OpenVINO version
-
static std::vector<std::uint8_t> getEmbeddedDeviceBinary(Config config)
Gets device firmware binary for a specific configuration
- Parameters:
config – FW with applied configuration
- Returns:
Firmware binary
-
static ProfilingData getGlobalProfilingData()
Get current global accumulated profiling data
- Returns:
ProfilingData from all devices
Public Static Attributes
-
static constexpr std::chrono::seconds DEFAULT_SEARCH_TIME = {10}
Default search time for constructors which discover devices.
-
static constexpr float DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ = {1.0f}
Default rate at which system information is logged.
-
static constexpr UsbSpeed DEFAULT_USB_SPEED = {UsbSpeed::SUPER}
Default UsbSpeed for device connection.
-
static constexpr std::chrono::milliseconds DEFAULT_TIMESYNC_PERIOD = {5000}
Default Timesync period.
-
static constexpr int DEFAULT_TIMESYNC_NUM_SAMPLES = {10}
Default Timesync number of samples per sync.
-
static constexpr bool DEFAULT_TIMESYNC_RANDOM = {true}
Default Timesync packet interval randomness.
Protected Functions
-
void tryStartPipeline(const Pipeline &pipeline)
a safe way to start a pipeline, which is closed if any exception occurs
-
virtual bool startPipelineImpl(const Pipeline &pipeline)
Allows the derived classes to handle custom setup for starting the pipeline
See also
Note
Remember to call this function in the overload to setup the communication properly
- Parameters:
pipeline – OpenVINO version of the pipeline must match the one which the device was booted with
- Returns:
True if pipeline started, false otherwise
-
virtual void closeImpl()
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
-
void init()
-
void init(const std::filesystem::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, UsbSpeed maxUsbSpeed)
-
void init(const Pipeline &pipeline, const DeviceInfo &devInfo, const std::filesystem::path &pathToCmd)
-
void init(const Pipeline &pipeline, UsbSpeed maxUsbSpeed, const std::filesystem::path &pathToMvcmd)
-
void init(Config config, const DeviceInfo &devInfo, UsbSpeed maxUsbSpeed)
-
void init(Config config, const DeviceInfo &devInfo, const std::filesystem::path &pathToCmd)
Protected Attributes
-
std::shared_ptr<XLinkConnection> connection
-
DeviceBase()