Go to the documentation of this file.
6 #include <condition_variable>
13 #include <type_traits>
14 #include <unordered_map>
111 static std::tuple<bool, DeviceInfo>
getAnyAvailableDevice(std::chrono::milliseconds timeout, std::function<
void()> cb);
173 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
203 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
240 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
270 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
342 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
365 template <typename T, std::enable_if_t<std::is_same<T, bool>::value,
bool> =
true>
410 [[deprecated(
"Device(pipeline) starts the pipeline automatically. See Device() and startPipeline(pipeline) otherwise")]]
bool startPipeline();
458 void setXLinkRateLimit(
int maxRateBytesPerSecond,
int burstSize = 0,
int waitUs = 0);
522 [[deprecated(
"Use setIrFloodLightIntensity(float intensity) instead.")]]
bool setIrFloodLightBrightness(
float mA,
int mask = -1);
554 std::vector<std::tuple<std::string, int, int>>
getIrDrivers();
884 void setTimesync(std::chrono::milliseconds period,
int numSamples,
bool random);
std::atomic< bool > watchdogRunning
CpuUsage getLeonCssCpuUsage()
CalibrationHandler getCalibration()
bool setIrLaserDotProjectorBrightness(float mA, int mask=-1)
DeviceInfo getDeviceInfo() const
Represents the pipeline, set of nodes and connections between them.
static constexpr bool DEFAULT_TIMESYNC_RANDOM
Default Timesync packet interval randomness.
std::atomic< bool > timesyncRunning
void init2(Config cfg, const dai::Path &pathToMvcmd, tl::optional< const Pipeline & > pipeline)
std::thread watchdogThread
static std::tuple< bool, DeviceInfo > getDeviceByMxId(std::string mxId)
bool setIrFloodLightBrightness(float mA, int mask=-1)
static ProfilingData getGlobalProfilingData()
Version
OpenVINO Version supported version information.
std::mutex lastWatchdogPingTimeMtx
MemoryInfo getLeonMssHeapUsage()
std::vector< std::tuple< std::string, int, int > > getIrDrivers()
std::atomic< bool > profilingRunning
void flashFactoryCalibration(CalibrationHandler calibrationHandler)
CalibrationHandler readFactoryCalibration()
CalibrationHandler readCalibrationOrDefault()
static constexpr std::chrono::seconds DEFAULT_SEARCH_TIME
Default search time for constructors which discover devices.
std::thread loggingThread
void setCalibration(CalibrationHandler calibrationDataHandler)
void setLogLevel(LogLevel level)
static constexpr int DEFAULT_TIMESYNC_NUM_SAMPLES
Default Timesync number of samples per sync.
void init(OpenVINO::Version version)
MemoryInfo getLeonCssHeapUsage()
std::atomic< bool > loggingRunning
void flashCalibration2(CalibrationHandler calibrationDataHandler)
void setLogOutputLevel(LogLevel level)
tl::optional< PipelineSchema > pipelineSchema
DeviceBase(OpenVINO::Version version, T usb2Mode)
std::thread profilingThread
float getSystemInformationLoggingRate()
std::vector< CameraFeatures > getConnectedCameraFeatures()
DeviceBase(const Pipeline &pipeline, T usb2Mode)
std::vector< std::uint8_t > readCalibrationRaw()
std::vector< std::uint8_t > readFactoryCalibrationRaw()
dai::Version getIMUFirmwareVersion()
std::string getProductName()
std::chrono::steady_clock::time_point lastWatchdogPingTime
MemoryInfo getCmxMemoryUsage()
CalibrationHandler readFactoryCalibrationOrDefault()
dai::Version getEmbeddedIMUFirmwareVersion()
std::vector< ConnectionInterface > getConnectionInterfaces()
std::string getConnectedIMU()
DeviceBase(OpenVINO::Version version, const DeviceInfo &devInfo, T usb2Mode)
std::thread timesyncThread
bool setIrFloodLightIntensity(float intensity, int mask=-1)
CalibrationHandler readCalibration()
DeviceBase(const Pipeline &pipeline, const DeviceInfo &devInfo, T usb2Mode)
tl::optional< LogLevel > logLevel
std::string getDeviceName()
virtual bool startPipelineImpl(const Pipeline &pipeline)
static std::vector< std::uint8_t > getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version=OpenVINO::VERSION_UNIVERSAL)
bool setIrLaserDotProjectorIntensity(float intensity, int mask=-1)
tl::optional< Version > getBootloaderVersion()
bool startIMUFirmwareUpdate(bool forceUpdate=false)
bool flashCalibration(CalibrationHandler calibrationDataHandler)
static constexpr std::chrono::milliseconds DEFAULT_TIMESYNC_PERIOD
Default Timesync period.
std::shared_ptr< XLinkConnection > connection
void setSystemInformationLoggingRate(float rateHz)
std::shared_ptr< const XLinkConnection > getConnection() const
std::mutex logCallbackMapMtx
std::unordered_map< CameraBoardSocket, std::string > getCameraSensorNames()
DeviceBase(Config config, const DeviceInfo &devInfo, T usb2Mode)
CalibrationHandler readCalibration2()
void tryStartPipeline(const Pipeline &pipeline)
a safe way to start a pipeline, which is closed if any exception occurs
std::shared_ptr< XLinkConnection > getConnection()
std::vector< StereoPair > getStereoPairs()
ProfilingData getProfilingData()
tl::optional< LogLevel > outputLogLevel
OpenVINO::Version version
void factoryResetCalibration()
static std::vector< DeviceInfo > getAllAvailableDevices()
LogLevel getLogOutputLevel()
void setXLinkChunkSize(int sizeBytes)
CpuUsage getLeonMssCpuUsage()
void setXLinkRateLimit(int maxRateBytesPerSecond, int burstSize=0, int waitUs=0)
static constexpr float DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ
Default rate at which system information is logged.
static std::vector< DeviceInfo > getAllConnectedDevices()
bool removeLogCallback(int callbackId)
std::vector< CameraBoardSocket > getConnectedCameras()
static std::tuple< bool, DeviceInfo > getAnyAvailableDevice()
static std::tuple< bool, DeviceInfo > getFirstAvailableDevice(bool skipInvalidDevice=true)
tl::optional< Version > bootloaderVersion
std::vector< StereoPair > getAvailableStereoPairs()
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
static std::chrono::milliseconds getDefaultSearchTime()
Get the Default Search Time for finding devices.
int addLogCallback(std::function< void(LogMessage)> callback)
std::thread monitorThread
ChipTemperature getChipTemperature()
void setTimesync(std::chrono::milliseconds period, int numSamples, bool random)
DeviceBase(Config config, T usb2Mode)
std::tuple< bool, unsigned int > getIMUFirmwareUpdateStatus()
void flashFactoryEepromClear()
static constexpr UsbSpeed DEFAULT_USB_SPEED
Default UsbSpeed for device connection.
MemoryInfo getDdrMemoryUsage()
std::unordered_map< int, std::function< void(LogMessage)> > logCallbackMap
dai::CrashDump getCrashDump(bool clearCrashDump=true)
depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:19