#include <DeviceBase.hpp>
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< 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 Member Functions | |
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 () |
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< XLinkConnection > | connection |
Private Member Functions | |
void | init2 (Config cfg, const dai::Path &pathToMvcmd, tl::optional< const Pipeline & > pipeline) |
void | tryGetDevice () |
Private Attributes | |
tl::optional< Version > | bootloaderVersion |
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< Impl > | pimpl |
tl::optional< PipelineSchema > | pipelineSchema |
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 |
The core of depthai device for RAII, connects to device and maintains watchdog, timesync, ...
Definition at line 50 of file DeviceBase.hpp.
|
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.
|
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.
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.
Connects to any available device with a DEFAULT_SEARCH_TIME timeout.
Definition at line 386 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase | ( | 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 391 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 | ( | 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 396 of file DeviceBase.cpp.
dai::DeviceBase::DeviceBase | ( | 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 401 of file DeviceBase.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 a DEFAULT_SEARCH_TIME timeout.
version | OpenVINO version which the device will be booted with. |
Definition at line 364 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 | ( | OpenVINO::Version | version, |
UsbSpeed | maxUsbSpeed | ||
) |
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 | ( | OpenVINO::Version | version, |
const dai::Path & | pathToCmd | ||
) |
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 | ( | OpenVINO::Version | version, |
const DeviceInfo & | devInfo | ||
) |
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.
|
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 | ( | OpenVINO::Version | version, |
const DeviceInfo & | devInfo, | ||
UsbSpeed | maxUsbSpeed | ||
) |
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.
dai::DeviceBase::DeviceBase | ( | OpenVINO::Version | version, |
const DeviceInfo & | devInfo, | ||
const dai::Path & | pathToCmd | ||
) |
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.
|
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 | ( | Config | config, |
const DeviceInfo & | devInfo | ||
) |
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.
|
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 | ( | const DeviceInfo & | devInfo, |
UsbSpeed | maxUsbSpeed | ||
) |
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.
dai::DeviceBase::DeviceBase | ( | std::string | nameOrDeviceId | ) |
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 | ( | std::string | nameOrDeviceId, |
UsbSpeed | maxUsbSpeed | ||
) |
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.
|
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.
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.
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.
|
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 | ( | Config | config, |
const DeviceInfo & | devInfo, | ||
UsbSpeed | maxUsbSpeed | ||
) |
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.
dai::DeviceBase::DeviceBase | ( | Config | config, |
const DeviceInfo & | devInfo, | ||
const dai::Path & | pathToCmd, | ||
bool | dumpOnly = false |
||
) |
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.
|
virtual |
Device destructor
Definition at line 632 of file DeviceBase.cpp.
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.
callback | Callback to call whenever a log message arrives |
Definition at line 1272 of file DeviceBase.cpp.
void dai::DeviceBase::close | ( | ) |
Explicitly closes connection to device.
Definition at line 516 of file DeviceBase.cpp.
|
protectedvirtual |
Allows the derived classes to handle custom setup for gracefully stopping the pipeline
Reimplemented in dai::Device.
Definition at line 536 of file DeviceBase.cpp.
void dai::DeviceBase::factoryResetCalibration | ( | ) |
Factory reset EEPROM data if factory backup is available.
std::runtime_exception | If factory reset was unsuccessful |
Definition at line 1444 of file DeviceBase.cpp.
bool dai::DeviceBase::flashCalibration | ( | CalibrationHandler | calibrationDataHandler | ) |
Stores the Calibration and Device information to the Device EEPROM
calibrationObj | CalibrationHandler object which is loaded with calibration information. |
Definition at line 1327 of file DeviceBase.cpp.
void dai::DeviceBase::flashCalibration2 | ( | CalibrationHandler | calibrationDataHandler | ) |
Stores the Calibration and Device information to the Device EEPROM
std::runtime_exception | if failed to flash the calibration |
calibrationObj | CalibrationHandler object which is loaded with calibration information. |
Definition at line 1336 of file DeviceBase.cpp.
void dai::DeviceBase::flashEepromClear | ( | ) |
Destructive action, deletes User area EEPROM contents Requires PROTECTED permissions
std::runtime_exception | if failed to flash the calibration |
Definition at line 1475 of file DeviceBase.cpp.
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
std::runtime_exception | if failed to flash the calibration |
Definition at line 1400 of file DeviceBase.cpp.
void dai::DeviceBase::flashFactoryEepromClear | ( | ) |
Destructive action, deletes Factory area EEPROM contents Requires FACTORY PROTECTED permissions
std::runtime_exception | if failed to flash the calibration |
Definition at line 1493 of file DeviceBase.cpp.
|
static |
Returns all available devices
Definition at line 228 of file DeviceBase.cpp.
|
static |
Returns information of all connected devices. The devices could be both connectable as well as already connected to devices.
Definition at line 238 of file DeviceBase.cpp.
|
static |
Gets any available device
Definition at line 206 of file DeviceBase.cpp.
|
static |
Waits for any available device with a timeout
timeout | duration of time to wait for the any device |
Definition at line 140 of file DeviceBase.cpp.
|
static |
Waits for any available device with a timeout
timeout | duration of time to wait for the any device |
cb | callback function called between pooling intervals |
Definition at line 144 of file DeviceBase.cpp.
std::vector< StereoPair > dai::DeviceBase::getAvailableStereoPairs | ( | ) |
Get stereo pairs taking into account the calibration and connected cameras.
getStereoPairs
.Definition at line 1040 of file DeviceBase.cpp.
tl::optional< Version > dai::DeviceBase::getBootloaderVersion | ( | ) |
Gets Bootloader version if it was booted through Bootloader
Definition at line 1188 of file DeviceBase.cpp.
CalibrationHandler dai::DeviceBase::getCalibration | ( | ) |
Retrieves the CalibrationHandler object containing the non-persistent calibration
std::runtime_exception | if failed to get the calibration |
Definition at line 1365 of file DeviceBase.cpp.
std::unordered_map< CameraBoardSocket, std::string > dai::DeviceBase::getCameraSensorNames | ( | ) |
Get sensor names for cameras that are connected to the device
Definition at line 1117 of file DeviceBase.cpp.
ChipTemperature dai::DeviceBase::getChipTemperature | ( | ) |
Retrieves current chip temperature as measured by device
Definition at line 1172 of file DeviceBase.cpp.
MemoryInfo dai::DeviceBase::getCmxMemoryUsage | ( | ) |
Retrieves current CMX memory information from device
Definition at line 1160 of file DeviceBase.cpp.
std::vector< CameraFeatures > dai::DeviceBase::getConnectedCameraFeatures | ( | ) |
Get cameras that are connected to the device with their features/properties
Definition at line 1109 of file DeviceBase.cpp.
std::vector< CameraBoardSocket > dai::DeviceBase::getConnectedCameras | ( | ) |
Get cameras that are connected to the device
Definition at line 1036 of file DeviceBase.cpp.
std::string dai::DeviceBase::getConnectedIMU | ( | ) |
|
inline |
Returns underlying XLinkConnection
Definition at line 912 of file DeviceBase.hpp.
|
inline |
Returns underlying XLinkConnection
Definition at line 919 of file DeviceBase.hpp.
std::vector< ConnectionInterface > dai::DeviceBase::getConnectionInterfaces | ( | ) |
Get connection interfaces for device
Definition at line 1105 of file DeviceBase.cpp.
dai::CrashDump dai::DeviceBase::getCrashDump | ( | bool | clearCrashDump = true | ) |
Retrieves crash dump for debugging.
Definition at line 1260 of file DeviceBase.cpp.
MemoryInfo dai::DeviceBase::getDdrMemoryUsage | ( | ) |
Retrieves current DDR memory information from device
Definition at line 1156 of file DeviceBase.cpp.
|
static |
Get the Default Search Time for finding devices.
Definition at line 124 of file DeviceBase.cpp.
|
static |
Finds a device by MX ID. Example: 14442C10D13EABCE00
mxId | MyraidX ID which uniquely specifies a device |
Definition at line 243 of file DeviceBase.cpp.
DeviceInfo dai::DeviceBase::getDeviceInfo | ( | ) | const |
Get the Device Info object o the device which is currently running
Definition at line 1216 of file DeviceBase.cpp.
std::string dai::DeviceBase::getDeviceName | ( | ) |
Get device name if available
Definition at line 1226 of file DeviceBase.cpp.
|
static |
Gets device firmware binary for a specific OpenVINO version
Definition at line 255 of file DeviceBase.cpp.
|
static |
Gets device firmware binary for a specific configuration
config | FW with applied configuration |
Definition at line 259 of file DeviceBase.cpp.
dai::Version dai::DeviceBase::getEmbeddedIMUFirmwareVersion | ( | ) |
Get embedded IMU firmware version to which IMU can be upgraded
Definition at line 1136 of file DeviceBase.cpp.
|
static |
Gets first available device. Device can be either in XLINK_UNBOOTED or XLINK_BOOTLOADER state
Definition at line 213 of file DeviceBase.cpp.
|
static |
Get current global accumulated profiling data
Definition at line 263 of file DeviceBase.cpp.
std::tuple< bool, unsigned int > dai::DeviceBase::getIMUFirmwareUpdateStatus | ( | ) |
Get IMU firmware update status
Definition at line 1151 of file DeviceBase.cpp.
dai::Version dai::DeviceBase::getIMUFirmwareVersion | ( | ) |
Get connected IMU firmware version
Definition at line 1125 of file DeviceBase.cpp.
std::vector< std::tuple< std::string, int, int > > dai::DeviceBase::getIrDrivers | ( | ) |
Retrieves detected IR laser/LED drivers.
[{"LM3644", 2, 0x63}]
Definition at line 1256 of file DeviceBase.cpp.
CpuUsage dai::DeviceBase::getLeonCssCpuUsage | ( | ) |
Retrieves average CSS Leon CPU usage
Definition at line 1176 of file DeviceBase.cpp.
MemoryInfo dai::DeviceBase::getLeonCssHeapUsage | ( | ) |
Retrieves current CSS Leon CPU heap information from device
Definition at line 1164 of file DeviceBase.cpp.
CpuUsage dai::DeviceBase::getLeonMssCpuUsage | ( | ) |
Retrieves average MSS Leon CPU usage
Definition at line 1180 of file DeviceBase.cpp.
MemoryInfo dai::DeviceBase::getLeonMssHeapUsage | ( | ) |
Retrieves current MSS Leon CPU heap information from device
Definition at line 1168 of file DeviceBase.cpp.
LogLevel dai::DeviceBase::getLogLevel | ( | ) |
Gets current logging severity level of the device.
Definition at line 1200 of file DeviceBase.cpp.
LogLevel dai::DeviceBase::getLogOutputLevel | ( | ) |
Gets logging level which decides printing level to standard output.
Definition at line 1236 of file DeviceBase.cpp.
std::string dai::DeviceBase::getMxId | ( | ) |
std::string dai::DeviceBase::getProductName | ( | ) |
Get product name if available
Definition at line 1220 of file DeviceBase.cpp.
ProfilingData dai::DeviceBase::getProfilingData | ( | ) |
Get current accumulated profiling data
Definition at line 1268 of file DeviceBase.cpp.
std::vector< StereoPair > dai::DeviceBase::getStereoPairs | ( | ) |
Get stereo pairs based on the device type.
Definition at line 1113 of file DeviceBase.cpp.
float dai::DeviceBase::getSystemInformationLoggingRate | ( | ) |
Gets current rate of system information logging ("info" severity) in Hz.
Definition at line 1319 of file DeviceBase.cpp.
UsbSpeed dai::DeviceBase::getUsbSpeed | ( | ) |
Retrieves USB connection speed
Definition at line 1184 of file DeviceBase.cpp.
int dai::DeviceBase::getXLinkChunkSize | ( | ) |
Gets current XLink chunk size.
Definition at line 1208 of file DeviceBase.cpp.
bool dai::DeviceBase::hasCrashDump | ( | ) |
Retrieves whether the is crash dump stored on device or not.
Definition at line 1264 of file DeviceBase.cpp.
Definition at line 492 of file DeviceBase.cpp.
|
protected |
Definition at line 502 of file DeviceBase.cpp.
|
protected |
Definition at line 497 of file DeviceBase.cpp.
Definition at line 487 of file DeviceBase.cpp.
|
protected |
Definition at line 663 of file DeviceBase.cpp.
|
protected |
Definition at line 445 of file DeviceBase.cpp.
Definition at line 458 of file DeviceBase.cpp.
|
protected |
Definition at line 466 of file DeviceBase.cpp.
|
protected |
|
protected |
Definition at line 479 of file DeviceBase.cpp.
|
protected |
Definition at line 474 of file DeviceBase.cpp.
Definition at line 453 of file DeviceBase.cpp.
|
protected |
Definition at line 657 of file DeviceBase.cpp.
|
protected |
Definition at line 422 of file DeviceBase.cpp.
|
protected |
Definition at line 431 of file DeviceBase.cpp.
|
protected |
Definition at line 440 of file DeviceBase.cpp.
|
protected |
Definition at line 649 of file DeviceBase.cpp.
|
private |
Definition at line 670 of file DeviceBase.cpp.
bool dai::DeviceBase::isClosed | ( | ) | const |
Is the device already closed (or disconnected)
Definition at line 627 of file DeviceBase.cpp.
bool dai::DeviceBase::isEepromAvailable | ( | ) |
Check if EEPROM is available
Definition at line 1323 of file DeviceBase.cpp.
bool dai::DeviceBase::isPipelineRunning | ( | ) |
Checks if devices pipeline is already running
Definition at line 1192 of file DeviceBase.cpp.
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
Definition at line 1376 of file DeviceBase.cpp.
CalibrationHandler dai::DeviceBase::readCalibration2 | ( | ) |
Fetches the EEPROM data from the device and loads it into CalibrationHandler object
std::runtime_exception | if no calibration is flashed |
Definition at line 1385 of file DeviceBase.cpp.
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
Definition at line 1396 of file DeviceBase.cpp.
std::vector< std::uint8_t > dai::DeviceBase::readCalibrationRaw | ( | ) |
Fetches the raw EEPROM data from User area
std::runtime_exception | if any error occurred |
Definition at line 1453 of file DeviceBase.cpp.
CalibrationHandler dai::DeviceBase::readFactoryCalibration | ( | ) |
Fetches the EEPROM data from Factory area and loads it into CalibrationHandler object
std::runtime_exception | if no calibration is flashed |
Definition at line 1424 of file DeviceBase.cpp.
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
Definition at line 1434 of file DeviceBase.cpp.
std::vector< std::uint8_t > dai::DeviceBase::readFactoryCalibrationRaw | ( | ) |
Fetches the raw EEPROM data from Factory area
std::runtime_exception | if any error occurred |
Definition at line 1464 of file DeviceBase.cpp.
bool dai::DeviceBase::removeLogCallback | ( | int | callbackId | ) |
Removes a callback
callbackId | Id of callback to be removed |
Definition at line 1286 of file DeviceBase.cpp.
void dai::DeviceBase::setCalibration | ( | CalibrationHandler | calibrationDataHandler | ) |
Sets the Calibration at runtime. This is not persistent and will be lost after device reset.
std::runtime_exception | if failed to set the calibration |
calibrationObj | CalibrationHandler object which is loaded with calibration information. |
Definition at line 1356 of file DeviceBase.cpp.
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
mA | Current in mA 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 |
Definition at line 1248 of file DeviceBase.cpp.
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
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 |
Definition at line 1252 of file DeviceBase.cpp.
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
mA | Current in mA 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 |
Definition at line 1240 of file DeviceBase.cpp.
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
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 |
Definition at line 1244 of file DeviceBase.cpp.
void dai::DeviceBase::setLogLevel | ( | LogLevel | level | ) |
Sets the devices logging severity level. This level affects which logs are transferred from device to host.
level | Logging severity |
Definition at line 1196 of file DeviceBase.cpp.
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
level | Standard output printing severity |
Definition at line 1232 of file DeviceBase.cpp.
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
rateHz | Logging rate in Hz |
Definition at line 1315 of file DeviceBase.cpp.
void dai::DeviceBase::setTimesync | ( | bool | enable | ) |
Enables or disables Timesync service on device. It keeps host and device clocks in sync.
enable | Enables or disables consistent timesyncing |
Definition at line 1307 of file DeviceBase.cpp.
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
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 |
Definition at line 1298 of file DeviceBase.cpp.
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.
sizeBytes | XLink chunk size in bytes |
Definition at line 1204 of file DeviceBase.cpp.
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
maxRateBytesPerSecond | Rate limit in Bytes/second |
burstSize | Size in Bytes for how much to attempt to send once, 0 = auto |
waitUs | Time in microseconds to wait for replenishing tokens, 0 = auto |
Definition at line 1212 of file DeviceBase.cpp.
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.
forceUpdate | Force firmware update or not. Will perform FW update regardless of current version and embedded firmware version. |
Definition at line 1147 of file DeviceBase.cpp.
bool dai::DeviceBase::startPipeline | ( | ) |
Starts the execution of the devices pipeline
Definition at line 1511 of file DeviceBase.cpp.
bool dai::DeviceBase::startPipeline | ( | const Pipeline & | pipeline | ) |
Starts the execution of a given pipeline
pipeline | OpenVINO version of the pipeline must match the one which the device was booted with. |
Definition at line 1516 of file DeviceBase.cpp.
|
protectedvirtual |
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 in dai::Device.
Definition at line 1525 of file DeviceBase.cpp.
|
private |
Definition at line 320 of file DeviceBase.cpp.
|
protected |
a safe way to start a pipeline, which is closed if any exception occurs
Definition at line 636 of file DeviceBase.cpp.
|
private |
Definition at line 975 of file DeviceBase.hpp.
|
private |
Definition at line 1005 of file DeviceBase.hpp.
|
mutableprivate |
Definition at line 1004 of file DeviceBase.hpp.
|
private |
Definition at line 1012 of file DeviceBase.hpp.
|
protected |
Definition at line 924 of file DeviceBase.hpp.
|
staticconstexpr |
Default search time for constructors which discover devices.
Definition at line 55 of file DeviceBase.hpp.
|
staticconstexpr |
Default rate at which system information is logged.
Definition at line 57 of file DeviceBase.hpp.
|
staticconstexpr |
Default Timesync number of samples per sync.
Definition at line 63 of file DeviceBase.hpp.
|
staticconstexpr |
Default Timesync period.
Definition at line 61 of file DeviceBase.hpp.
|
staticconstexpr |
Default Timesync packet interval randomness.
Definition at line 65 of file DeviceBase.hpp.
|
staticconstexpr |
Default UsbSpeed for device connection.
Definition at line 59 of file DeviceBase.hpp.
|
private |
Definition at line 974 of file DeviceBase.hpp.
|
private |
Definition at line 1015 of file DeviceBase.hpp.
|
private |
Definition at line 1014 of file DeviceBase.hpp.
|
private |
Definition at line 1001 of file DeviceBase.hpp.
|
private |
Definition at line 1000 of file DeviceBase.hpp.
|
private |
Definition at line 980 of file DeviceBase.hpp.
|
private |
Definition at line 979 of file DeviceBase.hpp.
|
private |
Definition at line 992 of file DeviceBase.hpp.
|
private |
Definition at line 991 of file DeviceBase.hpp.
|
private |
Definition at line 999 of file DeviceBase.hpp.
Definition at line 1008 of file DeviceBase.hpp.
|
private |
Definition at line 1018 of file DeviceBase.hpp.
|
private |
Definition at line 996 of file DeviceBase.hpp.
|
private |
Definition at line 995 of file DeviceBase.hpp.
|
private |
Definition at line 988 of file DeviceBase.hpp.
|
private |
Definition at line 987 of file DeviceBase.hpp.
|
private |
Definition at line 978 of file DeviceBase.hpp.
|
private |
Definition at line 984 of file DeviceBase.hpp.
|
private |
Definition at line 983 of file DeviceBase.hpp.