DeviceBase.cpp
Go to the documentation of this file.
2 
3 // std
4 #include <iostream>
5 
6 // shared
17 
18 // project
19 #include "DeviceLogger.hpp"
23 #include "pipeline/Pipeline.hpp"
25 #include "utility/Environment.hpp"
26 #include "utility/Files.hpp"
28 #include "utility/PimplImpl.hpp"
29 #include "utility/Resources.hpp"
30 #include "utility/spdlog-fmt.hpp"
31 
32 // libraries
33 #include "XLink/XLink.h"
34 #include "XLink/XLinkTime.h"
35 #include "nanorpc/core/client.h"
37 #include "spdlog/details/os.h"
38 #include "spdlog/fmt/bin_to_hex.h"
39 #include "spdlog/fmt/chrono.h"
40 #include "spdlog/sinks/stdout_color_sinks.h"
41 #include "spdlog/spdlog.h"
43 #include "utility/Logging.hpp"
44 
45 namespace dai {
46 
47 const std::string MAGIC_PROTECTED_FLASHING_VALUE = "235539980";
48 const std::string MAGIC_FACTORY_FLASHING_VALUE = "413424129";
49 const std::string MAGIC_FACTORY_PROTECTED_FLASHING_VALUE = "868632271";
50 
51 const unsigned int DEFAULT_CRASHDUMP_TIMEOUT = 9000;
52 
53 // local static function
54 static void getFlashingPermissions(bool& factoryPermissions, bool& protectedPermissions) {
55  auto permissionEnv = utility::getEnv("DEPTHAI_ALLOW_FACTORY_FLASHING");
56  if(permissionEnv == MAGIC_FACTORY_FLASHING_VALUE) {
57  factoryPermissions = true;
58  protectedPermissions = false;
59  } else if(permissionEnv == MAGIC_PROTECTED_FLASHING_VALUE) {
60  factoryPermissions = false;
61  protectedPermissions = true;
62  } else if(permissionEnv == MAGIC_FACTORY_PROTECTED_FLASHING_VALUE) {
63  factoryPermissions = true;
64  protectedPermissions = true;
65  } else {
66  factoryPermissions = false;
67  protectedPermissions = false;
68  }
69 }
70 
71 static LogLevel spdlogLevelToLogLevel(spdlog::level::level_enum level, LogLevel defaultValue = LogLevel::OFF) {
72  switch(level) {
74  return LogLevel::TRACE;
76  return LogLevel::DEBUG;
78  return LogLevel::INFO;
80  return LogLevel::WARN;
81  case spdlog::level::err:
82  return LogLevel::ERR;
84  return LogLevel::CRITICAL;
85  case spdlog::level::off:
86  return LogLevel::OFF;
87  // Default
88  case spdlog::level::n_levels:
89  default:
90  return defaultValue;
91  break;
92  }
93  // Default
94  return defaultValue;
95 }
96 static spdlog::level::level_enum logLevelToSpdlogLevel(LogLevel level, spdlog::level::level_enum defaultValue = spdlog::level::off) {
97  switch(level) {
98  case LogLevel::TRACE:
99  return spdlog::level::trace;
100  case LogLevel::DEBUG:
101  return spdlog::level::debug;
102  case LogLevel::INFO:
103  return spdlog::level::info;
104  case LogLevel::WARN:
105  return spdlog::level::warn;
106  case LogLevel::ERR:
107  return spdlog::level::err;
108  case LogLevel::CRITICAL:
110  case LogLevel::OFF:
111  return spdlog::level::off;
112  }
113  // Default
114  return defaultValue;
115 }
116 
117 constexpr std::chrono::seconds DeviceBase::DEFAULT_SEARCH_TIME;
120 constexpr std::chrono::milliseconds DeviceBase::DEFAULT_TIMESYNC_PERIOD;
123 
124 std::chrono::milliseconds DeviceBase::getDefaultSearchTime() {
125  std::chrono::milliseconds defaultSearchTime = DEFAULT_SEARCH_TIME;
126  auto searchTimeStr = utility::getEnv("DEPTHAI_SEARCH_TIMEOUT");
127 
128  if(!searchTimeStr.empty()) {
129  // Try parsing the string as a number
130  try {
131  defaultSearchTime = std::chrono::milliseconds{std::stoi(searchTimeStr)};
132  } catch(const std::invalid_argument& e) {
133  logger::warn("DEPTHAI_SEARCH_TIMEOUT value invalid: {}", e.what());
134  }
135  }
136 
137  return defaultSearchTime;
138 }
139 
140 std::tuple<bool, DeviceInfo> DeviceBase::getAnyAvailableDevice(std::chrono::milliseconds timeout) {
141  return getAnyAvailableDevice(timeout, nullptr);
142 }
143 
144 std::tuple<bool, DeviceInfo> DeviceBase::getAnyAvailableDevice(std::chrono::milliseconds timeout, std::function<void()> cb) {
145  using namespace std::chrono;
146  constexpr auto POOL_SLEEP_TIME = milliseconds(100);
147 
148  // First looks for UNBOOTED, then BOOTLOADER, for 'timeout' time
149  auto searchStartTime = steady_clock::now();
150  bool found = false;
152  std::unordered_map<std::string, DeviceInfo> invalidDevices;
153  do {
154  auto devices = XLinkConnection::getAllConnectedDevices(X_LINK_ANY_STATE, false);
155  for(auto searchState : {X_LINK_UNBOOTED, X_LINK_BOOTLOADER, X_LINK_FLASH_BOOTED}) {
156  for(const auto& device : devices) {
157  if(device.state == searchState) {
158  if(device.status == X_LINK_SUCCESS) {
159  found = true;
160  deviceInfo = device;
161  break;
162  } else {
163  found = false;
164  invalidDevices[device.name] = device;
165  }
166  }
167  }
168  if(found) break;
169  }
170  if(found) break;
171 
172  // Call the callback
173  if(cb) cb();
174 
175  // If 'timeout' < 'POOL_SLEEP_TIME', use 'timeout' as sleep time and then break
176  if(timeout < POOL_SLEEP_TIME) {
177  // sleep for 'timeout'
178  std::this_thread::sleep_for(timeout);
179  break;
180  } else {
181  std::this_thread::sleep_for(POOL_SLEEP_TIME); // default pool rate
182  }
183  } while(steady_clock::now() - searchStartTime < timeout);
184 
185  // Check if its an invalid device
186  for(const auto& invalidDevice : invalidDevices) {
187  const auto& invalidDeviceInfo = invalidDevice.second;
188  if(invalidDeviceInfo.status == X_LINK_INSUFFICIENT_PERMISSIONS) {
189  logger::warn("Insufficient permissions to communicate with {} device with name \"{}\". Make sure udev rules are set",
190  XLinkDeviceStateToStr(invalidDeviceInfo.state),
191  invalidDeviceInfo.name);
192  } else {
193  // Warn
194  logger::warn(
195  "Skipping {} device with name \"{}\" ({})", XLinkDeviceStateToStr(invalidDeviceInfo.state), invalidDeviceInfo.name, invalidDeviceInfo.mxid);
196  }
197  }
198 
199  // If none were found, try BOOTED
200  if(!found) std::tie(found, deviceInfo) = XLinkConnection::getFirstDevice(X_LINK_BOOTED);
201 
202  return {found, deviceInfo};
203 }
204 
205 // Default overload ('DEFAULT_SEARCH_TIME' timeout)
206 std::tuple<bool, DeviceInfo> DeviceBase::getAnyAvailableDevice() {
208 }
209 
210 // static api
211 
212 // First tries to find UNBOOTED device, then BOOTLOADER device
213 std::tuple<bool, DeviceInfo> DeviceBase::getFirstAvailableDevice(bool skipInvalidDevice) {
214  // Get all connected devices
215  auto devices = XLinkConnection::getAllConnectedDevices(X_LINK_ANY_STATE, skipInvalidDevice);
216  // Search order - first unbooted, then bootloader and last flash booted
217  for(auto searchState : {X_LINK_UNBOOTED, X_LINK_BOOTLOADER, X_LINK_FLASH_BOOTED}) {
218  for(const auto& device : devices) {
219  if(device.state == searchState) {
220  return {true, device};
221  }
222  }
223  }
224  return {false, {}};
225 }
226 
227 // Returns all devices which aren't already booted
228 std::vector<DeviceInfo> DeviceBase::getAllAvailableDevices() {
229  std::vector<DeviceInfo> availableDevices;
230  auto connectedDevices = XLinkConnection::getAllConnectedDevices();
231  for(const auto& d : connectedDevices) {
232  if(d.state != X_LINK_BOOTED) availableDevices.push_back(d);
233  }
234  return availableDevices;
235 }
236 
237 // Returns all devices, also the ones that are already booted
238 std::vector<DeviceInfo> DeviceBase::getAllConnectedDevices() {
240 }
241 
242 // First tries to find UNBOOTED device with mxId, then BOOTLOADER device with mxId
243 std::tuple<bool, DeviceInfo> DeviceBase::getDeviceByMxId(std::string mxId) {
244  std::vector<DeviceInfo> availableDevices;
245  auto states = {X_LINK_UNBOOTED, X_LINK_BOOTLOADER};
246  bool found;
247  DeviceInfo dev;
248  for(const auto& state : states) {
249  std::tie(found, dev) = XLinkConnection::getDeviceByMxId(mxId, state);
250  if(found) return {true, dev};
251  }
252  return {false, DeviceInfo()};
253 }
254 
255 std::vector<std::uint8_t> DeviceBase::getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version) {
256  return Resources::getInstance().getDeviceFirmware(usb2Mode, version);
257 }
258 
261 }
262 
265 }
266 
267 /*
268 std::vector<DeviceInfo> DeviceBase::getAllConnectedDevices(){
269  return XLinkConnection::getAllConnectedDevices();
270 }
271 
272 
273 std::tuple<bool, DeviceInfo> DeviceBase::getFirstDevice(){
274  return XLinkConnection::getFirstAvailableDevice();
275 }
276 */
277 
279 // Impl section - use this to hide dependencies
282  public:
283  Impl() = default;
284 
285  // Default sink
286  std::shared_ptr<spdlog::sinks::stdout_color_sink_mt> stdoutColorSink = std::make_shared<spdlog::sinks::stdout_color_sink_mt>();
287  // Device Logger
288  DeviceLogger logger{"host", stdoutColorSink};
289 
290  // RPC
291  std::mutex rpcMutex;
292  std::shared_ptr<XLinkStream> rpcStream;
293  std::unique_ptr<nanorpc::core::client<nanorpc::packer::nlohmann_msgpack>> rpcClient;
294 
295  void setLogLevel(LogLevel level);
297  void setPattern(const std::string& pattern);
298 };
299 
300 void DeviceBase::Impl::setPattern(const std::string& pattern) {
301  logger.set_pattern(pattern);
302 }
303 
305  // Converts LogLevel to spdlog and reconfigures logger level
306  auto spdlogLevel = logLevelToSpdlogLevel(level, spdlog::level::warn);
307  // Set level for all configured sinks
308  logger.set_level(spdlogLevel);
309 }
310 
312  // Converts spdlog to LogLevel
313  return spdlogLevelToLogLevel(logger.level(), LogLevel::WARN);
314 }
315 
317 // END OF Impl section
319 
321  // Searches for any available device for 'default' timeout
322  bool found = false;
323  std::tie(found, deviceInfo) = getAnyAvailableDevice();
324 
325  if(!found) {
326  auto numConnected = getAllAvailableDevices().size();
327  if(numConnected > 0) {
328  throw std::runtime_error("No available devices (" + std::to_string(numConnected) + " connected, but in use)");
329  }
330  auto numDevicesAnyPlatform = dai::XLinkConnection::getAllConnectedDevices(X_LINK_ANY_STATE, false, X_LINK_ANY_PLATFORM).size();
331  auto numDevicesRVC2 = dai::XLinkConnection::getAllConnectedDevices(X_LINK_ANY_STATE, false, X_LINK_MYRIAD_X).size();
332  auto nonRVC2Devices = numDevicesAnyPlatform - numDevicesRVC2;
333  if(nonRVC2Devices > 0) {
334  throw std::runtime_error("No available RVC2 devices found, but found " + std::to_string(nonRVC2Devices)
335  + " non RVC2 device[s]. To use RVC4 devices, please update DepthAI to version v3.x or newer.");
336  }
337  }
338 }
339 
341 
342 DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : deviceInfo(devInfo) {
343  init(version, maxUsbSpeed, "");
344 }
345 
346 DeviceBase::DeviceBase(OpenVINO::Version version, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) {
347  Config cfg;
348  cfg.version = version;
349 
350  init2(cfg, pathToCmd, {});
351 }
352 
353 DeviceBase::DeviceBase() : DeviceBase(OpenVINO::VERSION_UNIVERSAL) {}
354 
355 DeviceBase::DeviceBase(const DeviceInfo& devInfo) : DeviceBase(OpenVINO::VERSION_UNIVERSAL, devInfo) {}
356 
357 DeviceBase::DeviceBase(const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : DeviceBase(OpenVINO::VERSION_UNIVERSAL, devInfo, maxUsbSpeed) {}
358 
359 DeviceBase::DeviceBase(std::string nameOrDeviceId) : DeviceBase(OpenVINO::VERSION_UNIVERSAL, dai::DeviceInfo(std::move(nameOrDeviceId))) {}
360 
361 DeviceBase::DeviceBase(std::string nameOrDeviceId, UsbSpeed maxUsbSpeed)
362  : DeviceBase(OpenVINO::VERSION_UNIVERSAL, dai::DeviceInfo(std::move(nameOrDeviceId)), maxUsbSpeed) {}
363 
365  init(version);
366 }
367 
369  init(version, pathToCmd);
370 }
371 
373  init(version, maxUsbSpeed);
374 }
375 
377  init(pipeline);
378  tryStartPipeline(pipeline);
379 }
380 
381 DeviceBase::DeviceBase(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) {
382  init(pipeline, maxUsbSpeed);
383  tryStartPipeline(pipeline);
384 }
385 
386 DeviceBase::DeviceBase(const Pipeline& pipeline, const dai::Path& pathToCmd) {
387  init(pipeline, pathToCmd);
388  tryStartPipeline(pipeline);
389 }
390 
391 DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo) : deviceInfo(devInfo) {
392  init(pipeline, devInfo);
393  tryStartPipeline(pipeline);
394 }
395 
396 DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : deviceInfo(devInfo) {
397  init(pipeline, devInfo, maxUsbSpeed);
398  tryStartPipeline(pipeline);
399 }
400 
401 DeviceBase::DeviceBase(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) : deviceInfo(devInfo) {
402  init(pipeline, devInfo, pathToCmd);
403  tryStartPipeline(pipeline);
404 }
405 
406 DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) : deviceInfo(devInfo) {
407  init(config, maxUsbSpeed, "");
408 }
409 
410 DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd, bool dumpOnly) : deviceInfo(devInfo), dumpOnly(dumpOnly) {
411  init2(config, pathToCmd, {});
412 }
413 
414 DeviceBase::DeviceBase(Config config, const dai::Path& pathToCmd) {
415  init(config, pathToCmd);
416 }
417 
418 DeviceBase::DeviceBase(Config config, UsbSpeed maxUsbSpeed) {
419  init(config, maxUsbSpeed);
420 }
421 
423  tryGetDevice();
424 
425  Config cfg;
426  cfg.version = version;
427 
428  init2(cfg, "", {});
429 }
430 
431 void DeviceBase::init(OpenVINO::Version version, const dai::Path& pathToCmd) {
432  tryGetDevice();
433 
434  Config cfg;
435  cfg.version = version;
436 
437  init2(cfg, pathToCmd, {});
438 }
439 
440 void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed) {
441  tryGetDevice();
442  init(version, maxUsbSpeed, "");
443 }
444 
445 void DeviceBase::init(const Pipeline& pipeline) {
446  tryGetDevice();
447 
448  Config cfg = pipeline.getDeviceConfig();
449 
450  init2(cfg, "", pipeline);
451 }
452 
453 void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed) {
454  tryGetDevice();
455  init(pipeline, maxUsbSpeed, "");
456 }
457 
458 void DeviceBase::init(const Pipeline& pipeline, const dai::Path& pathToCmd) {
459  tryGetDevice();
460 
461  Config cfg = pipeline.getDeviceConfig();
462 
463  init2(cfg, pathToCmd, pipeline);
464 }
465 
466 void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo) {
467  deviceInfo = devInfo;
468 
469  Config cfg = pipeline.getDeviceConfig();
470 
471  init2(cfg, "", pipeline);
472 }
473 
474 void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) {
475  deviceInfo = devInfo;
476  init(pipeline, maxUsbSpeed, "");
477 }
478 
479 void DeviceBase::init(const Pipeline& pipeline, const DeviceInfo& devInfo, const dai::Path& pathToCmd) {
480  deviceInfo = devInfo;
481 
482  Config cfg = pipeline.getDeviceConfig();
483 
484  init2(cfg, pathToCmd, pipeline);
485 }
486 
487 void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed) {
488  tryGetDevice();
489  init(config, maxUsbSpeed, "");
490 }
491 
492 void DeviceBase::init(Config config, const dai::Path& pathToCmd) {
493  tryGetDevice();
494  init2(config, pathToCmd, {});
495 }
496 
497 void DeviceBase::init(Config config, const DeviceInfo& devInfo, UsbSpeed maxUsbSpeed) {
498  deviceInfo = devInfo;
499  init(config, maxUsbSpeed, "");
500 }
501 
502 void DeviceBase::init(Config config, const DeviceInfo& devInfo, const dai::Path& pathToCmd) {
503  deviceInfo = devInfo;
504  init2(config, pathToCmd, {});
505 }
506 
508  tryGetDevice();
509  init2(config, {}, {});
510 }
511 
512 DeviceBase::DeviceBase(Config config, const DeviceInfo& devInfo) : deviceInfo(devInfo) {
513  init2(config, {}, {});
514 }
515 
517  std::unique_lock<std::mutex> lock(closedMtx);
518  if(!closed) {
519  closeImpl();
520  closed = true;
521  }
522 }
523 
524 unsigned int getCrashdumpTimeout(XLinkProtocol_t protocol) {
525  std::string timeoutStr = utility::getEnv("DEPTHAI_CRASHDUMP_TIMEOUT");
526  if(!timeoutStr.empty()) {
527  try {
528  return std::stoi(timeoutStr) * 1000;
529  } catch(const std::invalid_argument& e) {
530  logger::warn("DEPTHAI_CRASHDUMP_TIMEOUT value invalid: {}", e.what());
531  }
532  }
534 }
535 
537  using namespace std::chrono;
538  auto t1 = steady_clock::now();
539  bool shouldGetCrashDump = false;
540  if(!dumpOnly) {
541  pimpl->logger.debug("Device about to be closed...");
542  try {
543  if(hasCrashDump()) {
544  connection->setRebootOnDestruction(true);
545  auto dump = getCrashDump();
547  } else {
548  bool isRunning = pimpl->rpcClient->call("isRunning").as<bool>();
549  shouldGetCrashDump = !isRunning;
550  connection->setRebootOnDestruction(connection->getRebootOnDestruction() || shouldGetCrashDump);
551  pimpl->logger.debug("Shutdown {}", isRunning ? "OK" : "error");
552  }
553  } catch(const std::exception& ex) {
554  pimpl->logger.debug("shutdown call error: {}", ex.what());
555  shouldGetCrashDump = true;
556  }
557  }
558 
559  // Close connection first; causes Xlink internal calls to unblock semaphore waits and
560  // return error codes, which then allows queues to unblock
561  // always manage ownership because other threads (e.g. watchdog) are running and need to
562  // keep the shared_ptr valid (even if closed). Otherwise leads to using null pointers,
563  // invalid memory, etc. which hard crashes main app
564  connection->close();
565 
566  watchdogRunning = false;
567  // Stop watchdog first (this resets and waits for link to fall down)
568  if(watchdogThread.joinable()) watchdogThread.join();
569 
570  // Stop various threads
571  timesyncRunning = false;
572  loggingRunning = false;
573  profilingRunning = false;
574 
575  // Then stop timesync
576  if(timesyncThread.joinable()) timesyncThread.join();
577  // And at the end stop logging thread
578  if(loggingThread.joinable()) loggingThread.join();
579  // And at the end stop profiling thread
580  if(profilingThread.joinable()) profilingThread.join();
581  // At the end stop the monitor thread
582  if(monitorThread.joinable()) monitorThread.join();
583 
584  // Close rpcStream
585  pimpl->rpcStream = nullptr;
586  pimpl->rpcClient = nullptr;
587 
588  if(!dumpOnly) {
589  auto timeout = getCrashdumpTimeout(deviceInfo.protocol);
590  // Get crash dump if needed
591  if(shouldGetCrashDump && timeout > 0) {
592  pimpl->logger.debug("Getting crash dump...");
593  auto t1 = steady_clock::now();
594  bool gotDump = false;
595  bool found = false;
596  do {
597  DeviceInfo rebootingDeviceInfo;
598  std::tie(found, rebootingDeviceInfo) = XLinkConnection::getDeviceByMxId(deviceInfo.getMxId(), X_LINK_ANY_STATE, false);
599  if(found && (rebootingDeviceInfo.state == X_LINK_UNBOOTED || rebootingDeviceInfo.state == X_LINK_BOOTLOADER)) {
600  pimpl->logger.trace("Found rebooting device in {}ns", duration_cast<nanoseconds>(steady_clock::now() - t1).count());
601  DeviceBase rebootingDevice(config, rebootingDeviceInfo, firmwarePath, true);
602  if(rebootingDevice.hasCrashDump()) {
603  auto dump = rebootingDevice.getCrashDump();
605 
606  } else {
607  pimpl->logger.warn("Device crashed, but no crash dump could be extracted.");
608  }
609  gotDump = true;
610  break;
611  }
612  } while(!found && steady_clock::now() - t1 < std::chrono::milliseconds(timeout));
613  if(!gotDump) {
614  pimpl->logger.error("Device likely crashed but did not reboot in time to get the crash dump");
615  }
616  } else if(shouldGetCrashDump) {
617  pimpl->logger.warn("Device crashed. Crash dump retrieval disabled.");
618  }
619 
620  pimpl->logger.debug("Device closed, {}", duration_cast<milliseconds>(steady_clock::now() - t1).count());
621  }
622 }
623 
624 // This function is thread-unsafe. The idea of "isClosed" is ephemerial and
625 // is invalidated during the return by value and continues to degrade in
626 // validity to the caller
627 bool DeviceBase::isClosed() const {
628  std::unique_lock<std::mutex> lock(closedMtx);
629  return closed || !watchdogRunning;
630 }
631 
634 }
635 
636 void DeviceBase::tryStartPipeline(const Pipeline& pipeline) {
637  try {
638  if(!startPipeline(pipeline)) {
639  throw std::runtime_error("Couldn't start the pipeline");
640  }
641  } catch(const std::exception&) {
642  // close device (cleanup)
643  close();
644  // Rethrow original exception
645  throw;
646  }
647 }
648 
649 void DeviceBase::init(OpenVINO::Version version, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) {
650  Config cfg;
651  // Specify usb speed
652  cfg.board.usb.maxSpeed = maxUsbSpeed;
653  // Specify the OpenVINO version
654  cfg.version = version;
655  init2(cfg, pathToMvcmd, {});
656 }
657 void DeviceBase::init(const Pipeline& pipeline, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) {
658  Config cfg = pipeline.getDeviceConfig();
659  // Modify usb speed
660  cfg.board.usb.maxSpeed = maxUsbSpeed;
661  init2(cfg, pathToMvcmd, pipeline);
662 }
663 void DeviceBase::init(Config config, UsbSpeed maxUsbSpeed, const dai::Path& pathToMvcmd) {
664  Config cfg = config;
665  // Modify usb speed
666  cfg.board.usb.maxSpeed = maxUsbSpeed;
667  init2(cfg, pathToMvcmd, {});
668 }
669 
670 void DeviceBase::init2(Config cfg, const dai::Path& pathToMvcmd, tl::optional<const Pipeline&> pipeline) {
671  // Initalize depthai library if not already
672  if(!dumpOnly) initialize();
673 
674  // Specify cfg
675  config = cfg;
676  firmwarePath = pathToMvcmd;
677 
678  // Apply nonExclusiveMode
680 
681  // Apply device specific logger level
682  {
685  }
686 
687  // Specify expected running mode
688  XLinkDeviceState_t expectedBootState = X_LINK_BOOTED;
690  expectedBootState = X_LINK_BOOTED_NON_EXCLUSIVE;
691  }
692 
693  // If deviceInfo isn't fully specified (eg ANY_STATE, etc...), try finding it first
694  if(deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.protocol == X_LINK_ANY_PROTOCOL) {
695  deviceDesc_t foundDesc;
696  auto ret = XLinkFindFirstSuitableDevice(deviceInfo.getXLinkDeviceDesc(), &foundDesc);
697  if(ret == X_LINK_SUCCESS) {
698  deviceInfo = DeviceInfo(foundDesc);
699  pimpl->logger.debug("Found an actual device by given DeviceInfo: {}", deviceInfo.toString());
700  } else {
701  deviceInfo.state = X_LINK_ANY_STATE;
702  pimpl->logger.debug("Searched, but no actual device found by given DeviceInfo");
703  }
704  }
705 
706  if(pipeline) {
707  pimpl->logger.debug("Device - pipeline serialized, OpenVINO version: {}", OpenVINO::getVersionName(config.version));
708  } else {
709  pimpl->logger.debug("Device - OpenVINO version: {}", OpenVINO::getVersionName(config.version));
710  }
711 
712  // Set logging pattern of device (device id + shared pattern)
713  pimpl->setPattern(fmt::format("[{}] [{}] {}", deviceInfo.mxid, deviceInfo.name, LOG_DEFAULT_PATTERN));
714 
715  // Check if WD env var is set
716  std::chrono::milliseconds watchdogTimeout = device::XLINK_USB_WATCHDOG_TIMEOUT;
717  if(deviceInfo.protocol == X_LINK_TCP_IP) {
718  watchdogTimeout = device::XLINK_TCP_WATCHDOG_TIMEOUT;
719  }
720  auto watchdogMsStr = utility::getEnv("DEPTHAI_WATCHDOG");
721  if(!watchdogMsStr.empty()) {
722  // Try parsing the string as a number
723  try {
724  std::chrono::milliseconds watchdog{std::stoi(watchdogMsStr)};
725  config.board.watchdogTimeoutMs = static_cast<uint32_t>(watchdog.count());
726  watchdogTimeout = watchdog;
727  if(watchdogTimeout.count() == 0) {
728  pimpl->logger.warn("Watchdog disabled! In case of unclean exit, the device needs reset or power-cycle for next run", watchdogTimeout);
729  } else {
730  pimpl->logger.warn("Using a custom watchdog value of {}", watchdogTimeout);
731  }
732  } catch(const std::invalid_argument& e) {
733  pimpl->logger.warn("DEPTHAI_WATCHDOG value invalid: {}", e.what());
734  }
735  }
736 
737  auto watchdogInitMsStr = utility::getEnv("DEPTHAI_WATCHDOG_INITIAL_DELAY");
738  if(!watchdogInitMsStr.empty()) {
739  // Try parsing the string as a number
740  try {
741  std::chrono::milliseconds watchdog{std::stoi(watchdogInitMsStr)};
742  config.board.watchdogInitialDelayMs = static_cast<uint32_t>(watchdog.count());
743  pimpl->logger.warn("Watchdog initial delay set to {}", watchdog);
744  } catch(const std::invalid_argument& e) {
745  pimpl->logger.warn("DEPTHAI_WATCHDOG_INITIAL_DELAY value invalid: {}", e.what());
746  }
747  }
748 
749  auto deviceDebugStr = utility::getEnv("DEPTHAI_DEBUG");
750  if(!deviceDebugStr.empty()) {
751  // Try parsing the string as a number
752  try {
753  int deviceDebug{std::stoi(deviceDebugStr)};
754  config.board.logDevicePrints = deviceDebug;
755  } catch(const std::invalid_argument& e) {
756  pimpl->logger.warn("DEPTHAI_DEBUG value invalid: {}, should be a number (non-zero to enable)", e.what());
757  }
758  }
759 
760  // Get embedded mvcmd or external with applied config
762  nlohmann::json jBoardConfig = config.board;
763  pimpl->logger.debug("Device - BoardConfig: {} \nlibnop:{}", jBoardConfig.dump(), spdlog::to_hex(utility::serialize(config.board)));
764  }
765  std::vector<std::uint8_t> fwWithConfig = Resources::getInstance().getDeviceFirmware(config, pathToMvcmd);
766 
767  // Init device (if bootloader, handle correctly - issue USB boot command)
768  if(deviceInfo.state == X_LINK_UNBOOTED) {
769  // Unbooted device found, boot and connect with XLinkConnection constructor
770  connection = std::make_shared<XLinkConnection>(deviceInfo, fwWithConfig);
771  } else if(deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
772  // Scope so DeviceBootloader is disconnected
773  {
775  auto version = bl.getVersion();
776  // Save DeviceBootloader version, to be able to retrieve later optionally
777  bootloaderVersion = version;
778 
779  // If version is >= 0.0.12 then boot directly, otherwise jump to USB ROM bootloader
780  // Check if version is recent enough for this operation
781  if(version >= DeviceBootloader::Version(0, 0, 12)) {
782  using namespace std::chrono;
783  // Boot the given FW
784  auto t1 = steady_clock::now();
785  bl.bootMemory(fwWithConfig);
786  auto t2 = steady_clock::now();
787  pimpl->logger.debug("Booting FW with Bootloader. Version {}, Time taken: {}", version.toString(), duration_cast<milliseconds>(t2 - t1));
788 
789  // After that the state will be expectedBootState
790  deviceInfo.state = expectedBootState;
791  } else {
792  // Boot into USB ROM BOOTLOADER
794  pimpl->logger.debug("Booting FW by jumping to USB ROM Bootloader first. Bootloader Version {}", version.toString());
795 
796  // After that the state will be UNBOOTED
797  deviceInfo.state = X_LINK_UNBOOTED;
798  }
799  }
800 
801  // Boot and connect with XLinkConnection constructor
802  connection = std::make_shared<XLinkConnection>(deviceInfo, fwWithConfig, expectedBootState);
803 
804  } else if(deviceInfo.state == X_LINK_BOOTED) {
805  // Connect without booting
806  connection = std::make_shared<XLinkConnection>(deviceInfo, fwWithConfig, expectedBootState);
807  } else {
808  throw std::runtime_error("Cannot find any device with given deviceInfo");
809  }
810 
811  deviceInfo.state = expectedBootState;
812 
813  // prepare rpc for both attached and host controlled mode
814  pimpl->rpcStream = std::make_shared<XLinkStream>(connection, device::XLINK_CHANNEL_MAIN_RPC, device::XLINK_USB_BUFFER_MAX_SIZE);
815  auto rpcStream = pimpl->rpcStream;
816 
817  pimpl->rpcClient = std::make_unique<nanorpc::core::client<nanorpc::packer::nlohmann_msgpack>>([this, rpcStream](nanorpc::core::type::buffer request) {
818  // Lock for time of the RPC call, to not mix the responses between calling threads.
819  // Note: might cause issues on Windows on incorrect shutdown. To be investigated
820  std::unique_lock<std::mutex> lock(pimpl->rpcMutex);
821 
822  // Log the request data
824  pimpl->logger.trace("RPC: {}", nlohmann::json::from_msgpack(request).dump());
825  }
826 
827  try {
828  // Send request to device
829  rpcStream->write(std::move(request));
830 
831  // Receive response back
832  // Send to nanorpc to parse
833  return rpcStream->read();
834  } catch(const std::exception& e) {
835  // If any exception is thrown, log it and rethrow
836  pimpl->logger.debug("RPC error: {}", e.what());
837  throw std::system_error(std::make_error_code(std::errc::io_error), "Device already closed or disconnected");
838  }
839  });
840 
841  // prepare watchdog thread, which will keep device alive
842  // separate stream so it doesn't miss between potentially long RPC calls
843  // Only create the thread if watchdog is enabled
844  if(watchdogTimeout > std::chrono::milliseconds(0)) {
845  // Specify "last" ping time (5s in the future, for some grace time)
846  {
847  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
848  lastWatchdogPingTime = std::chrono::steady_clock::now() + std::chrono::seconds(5);
849  }
850 
851  // Start watchdog thread for device
852  watchdogThread = std::thread([this, watchdogTimeout]() {
853  try {
855  std::vector<uint8_t> watchdogKeepalive = {0, 0, 0, 0};
856  while(watchdogRunning) {
857  stream.write(watchdogKeepalive);
858  {
859  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
860  lastWatchdogPingTime = std::chrono::steady_clock::now();
861  }
862  // Ping with a period half of that of the watchdog timeout
863  std::this_thread::sleep_for(watchdogTimeout / 2);
864  }
865  } catch(const std::exception& ex) {
866  // ignore
867  pimpl->logger.debug("Watchdog thread exception caught: {}", ex.what());
868  }
869 
870  // Watchdog ended. Useful for checking disconnects
871  watchdogRunning = false;
872  });
873 
874  // Start monitor thread for host - makes sure that device is responding to pings, otherwise it disconnects
875  monitorThread = std::thread([this, watchdogTimeout]() {
876  while(watchdogRunning) {
877  // Ping with a period half of that of the watchdog timeout
878  std::this_thread::sleep_for(watchdogTimeout);
879  // Check if wd was pinged in the specified watchdogTimeout time.
880  decltype(lastWatchdogPingTime) prevPingTime;
881  {
882  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
883  prevPingTime = lastWatchdogPingTime;
884  }
885  // Recheck if watchdogRunning wasn't already closed and close if more than twice of WD passed
886  if(watchdogRunning && std::chrono::steady_clock::now() - prevPingTime > watchdogTimeout * 2) {
887  pimpl->logger.warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name);
888  // ping was missed, reset the device
889  watchdogRunning = false;
890  // close the underlying connection
891  connection->close();
892  }
893  }
894  });
895 
896  } else {
897  // Still set watchdogRunning explictitly
898  // as it indicates device not being closed
899  watchdogRunning = true;
900  }
901 
902  if(!dumpOnly) {
903  // Below can throw - make sure to gracefully exit threads
904  try {
907 
908  // Sets system inforation logging rate. By default 1s
910  } catch(const std::exception&) {
911  // close device (cleanup)
912  close();
913  // Rethrow original exception
914  throw;
915  }
916 
917  // prepare timesync thread, which will keep device synchronized
918  timesyncThread = std::thread([this]() {
919  using namespace std::chrono;
920 
921  try {
923  while(timesyncRunning) {
924  // Block
925  XLinkTimespec timestamp;
926  stream.read(timestamp);
927 
928  // Write timestamp back
929  stream.write(&timestamp, sizeof(timestamp));
930  }
931  } catch(const std::exception& ex) {
932  // ignore
933  pimpl->logger.debug("Timesync thread exception caught: {}", ex.what());
934  }
935 
936  timesyncRunning = false;
937  });
938 
939  // prepare logging thread, which will log device messages
940  loggingThread = std::thread([this]() {
941  using namespace std::chrono;
942  std::vector<LogMessage> messages;
943  try {
945  while(loggingRunning) {
946  // Block
947  auto log = stream.read();
948 
949  try {
950  // Deserialize incoming messages
951  utility::deserialize(log, messages);
952 
953  pimpl->logger.trace("Log vector decoded, size: {}", messages.size());
954 
955  // log the messages in incremental order (0 -> size-1)
956  for(const auto& msg : messages) {
957  pimpl->logger.logMessage(msg);
958  }
959 
960  // Log to callbacks
961  {
962  // lock mtx to callback map (shared)
963  std::unique_lock<std::mutex> l(logCallbackMapMtx);
964  for(const auto& msg : messages) {
965  for(const auto& kv : logCallbackMap) {
966  const auto& cb = kv.second;
967  // If available, callback with msg
968  if(cb) cb(msg);
969  }
970  }
971  }
972 
973  } catch(const nlohmann::json::exception& ex) {
974  pimpl->logger.error("Exception while parsing or calling callbacks for log message from device: {}", ex.what());
975  }
976  }
977  } catch(const std::exception& ex) {
978  // ignore exception from logging
979  pimpl->logger.debug("Log thread exception caught: {}", ex.what());
980  }
981 
982  loggingRunning = false;
983  });
984 
985  if(utility::getEnv("DEPTHAI_PROFILING") == "1") {
986  // prepare profiling thread, which will log device messages
987  profilingThread = std::thread([this]() {
988  using namespace std::chrono;
989  try {
990  ProfilingData lastData = {};
991  // TODO(themarpe) - expose
992  float rate = 1.0f;
993  while(profilingRunning) {
995  long long w = data.numBytesWritten - lastData.numBytesWritten;
996  long long r = data.numBytesRead - lastData.numBytesRead;
997  w = static_cast<long long>(w / rate);
998  r = static_cast<long long>(r / rate);
999 
1000  lastData = data;
1001 
1002  pimpl->logger.debug("Profiling write speed: {:.2f} MiB/s, read speed: {:.2f} MiB/s, total written: {:.2f} MiB, read: {:.2f} MiB",
1003  w / 1024.0f / 1024.0f,
1004  r / 1024.0f / 1024.0f,
1005  data.numBytesWritten / 1024.0f / 1024.0f,
1006  data.numBytesRead / 1024.0f / 1024.0f);
1007 
1008  std::this_thread::sleep_for(duration<float>(1) / rate);
1009  }
1010  } catch(const std::exception& ex) {
1011  // ignore exception from logging
1012  pimpl->logger.debug("Profiling thread exception caught: {}", ex.what());
1013  }
1014 
1015  profilingRunning = false;
1016  });
1017  }
1018 
1019  // Below can throw - make sure to gracefully exit threads
1020  try {
1021  // Starts and waits for inital timesync
1023  } catch(const std::exception&) {
1024  // close device (cleanup)
1025  close();
1026  // Rethrow original exception
1027  throw;
1028  }
1029  }
1030 }
1031 
1032 std::string DeviceBase::getMxId() {
1033  return pimpl->rpcClient->call("getMxId").as<std::string>();
1034 }
1035 
1036 std::vector<CameraBoardSocket> DeviceBase::getConnectedCameras() {
1037  return pimpl->rpcClient->call("getConnectedCameras").as<std::vector<CameraBoardSocket>>();
1038 }
1039 
1040 std::vector<StereoPair> DeviceBase::getAvailableStereoPairs() {
1041  std::vector<dai::StereoPair> stereoPairs;
1042  dai::CalibrationHandler calibHandler;
1043  try {
1044  calibHandler = readCalibration2();
1045  if(calibHandler.getEepromData().cameraData.empty()) {
1046  throw std::runtime_error("No camera data found.");
1047  }
1048  } catch(const std::exception&) {
1049  try {
1050  calibHandler = readFactoryCalibration();
1051  } catch(const std::exception&) {
1052  pimpl->logger.info("No calibration found.");
1053  return stereoPairs;
1054  }
1055  }
1056  // Find links between cameras.
1057  for(auto const& camIdAndInfo1 : calibHandler.getEepromData().cameraData) {
1058  auto camId1 = camIdAndInfo1.first;
1059  for(auto const& camIdAndInfo2 : calibHandler.getEepromData().cameraData) {
1060  auto camId2 = camIdAndInfo2.first;
1061  try {
1062  auto translationVector = calibHandler.getCameraTranslationVector(camId1, camId2, false);
1063  auto baseline = std::abs(translationVector[0]) > std::abs(translationVector[1]) ? translationVector[0] : translationVector[1]; // X or Y
1064  auto leftSocket = baseline < 0 ? camId1 : camId2;
1065  auto rightSocket = leftSocket == camId1 ? camId2 : camId1;
1066  int baselineDiff = std::abs(static_cast<int>(translationVector[0]) - static_cast<int>(translationVector[1]));
1067  if(baselineDiff == static_cast<int>(std::abs(baseline))) {
1068  if(std::find_if(stereoPairs.begin(),
1069  stereoPairs.end(),
1070  [&leftSocket, &rightSocket](const dai::StereoPair& pair) { return pair.left == leftSocket && pair.right == rightSocket; })
1071  == stereoPairs.end()) {
1072  stereoPairs.push_back(dai::StereoPair{leftSocket, rightSocket, std::abs(baseline), static_cast<int>(translationVector[0]) == 0});
1073  }
1074  } else {
1075  pimpl->logger.debug("Skipping diagonal pair, left: {}, right: {}.", leftSocket, rightSocket);
1076  }
1077  } catch(const std::exception&) {
1078  continue;
1079  }
1080  }
1081  }
1082  // Filter out undetected cameras and socket pairs which are not present in getStereoPairs
1083  auto deviceStereoPairs = getStereoPairs();
1084  auto connectedCameras = getConnectedCameras();
1085  std::vector<dai::StereoPair> filteredStereoPairs;
1086  std::copy_if(
1087  stereoPairs.begin(), stereoPairs.end(), std::back_inserter(filteredStereoPairs), [this, connectedCameras, deviceStereoPairs](dai::StereoPair pair) {
1088  if(std::find(connectedCameras.begin(), connectedCameras.end(), pair.left) == connectedCameras.end()) {
1089  pimpl->logger.debug("Skipping calibrated stereo pair because, camera {} was not detected.", pair.left);
1090  return false;
1091  } else if(std::find(connectedCameras.begin(), connectedCameras.end(), pair.right) == connectedCameras.end()) {
1092  pimpl->logger.debug("Skipping calibrated stereo pair because, camera {} was not detected.", pair.right);
1093  return false;
1094  }
1095  return std::find_if(deviceStereoPairs.begin(),
1096  deviceStereoPairs.end(),
1097  [pair](dai::StereoPair devicePair) { return devicePair.left == pair.left && devicePair.right == pair.right; })
1098  != deviceStereoPairs.end();
1099  });
1100 
1101  std::sort(filteredStereoPairs.begin(), filteredStereoPairs.end(), [](dai::StereoPair a, dai::StereoPair b) { return a.baseline < b.baseline; });
1102  return filteredStereoPairs;
1103 }
1104 
1105 std::vector<ConnectionInterface> DeviceBase::getConnectionInterfaces() {
1106  return pimpl->rpcClient->call("getConnectionInterfaces").as<std::vector<ConnectionInterface>>();
1107 }
1108 
1109 std::vector<CameraFeatures> DeviceBase::getConnectedCameraFeatures() {
1110  return pimpl->rpcClient->call("getConnectedCameraFeatures").as<std::vector<CameraFeatures>>();
1111 }
1112 
1113 std::vector<StereoPair> DeviceBase::getStereoPairs() {
1114  return pimpl->rpcClient->call("getStereoPairs").as<std::vector<StereoPair>>();
1115 }
1116 
1117 std::unordered_map<CameraBoardSocket, std::string> DeviceBase::getCameraSensorNames() {
1118  return pimpl->rpcClient->call("getCameraSensorNames").as<std::unordered_map<CameraBoardSocket, std::string>>();
1119 }
1120 
1122  return pimpl->rpcClient->call("getConnectedIMU").as<std::string>();
1123 }
1124 
1126  std::string versionStr = pimpl->rpcClient->call("getIMUFirmwareVersion").as<std::string>();
1127  try {
1128  dai::Version version = dai::Version(versionStr);
1129  return version;
1130  } catch(const std::exception&) {
1131  dai::Version version = dai::Version(0, 0, 0);
1132  return version;
1133  }
1134 }
1135 
1137  std::string versionStr = pimpl->rpcClient->call("getEmbeddedIMUFirmwareVersion").as<std::string>();
1138  try {
1139  dai::Version version = dai::Version(versionStr);
1140  return version;
1141  } catch(const std::exception&) {
1142  dai::Version version = dai::Version(0, 0, 0);
1143  return version;
1144  }
1145 }
1146 
1147 bool DeviceBase::startIMUFirmwareUpdate(bool forceUpdate) {
1148  return pimpl->rpcClient->call("startIMUFirmwareUpdate", forceUpdate).as<bool>();
1149 }
1150 
1151 std::tuple<bool, unsigned int> DeviceBase::getIMUFirmwareUpdateStatus() {
1152  return pimpl->rpcClient->call("getIMUFirmwareUpdateStatus").as<std::tuple<bool, unsigned int>>();
1153 }
1154 
1155 // Convenience functions for querying current system information
1157  return pimpl->rpcClient->call("getDdrUsage").as<MemoryInfo>();
1158 }
1159 
1161  return pimpl->rpcClient->call("getCmxUsage").as<MemoryInfo>();
1162 }
1163 
1165  return pimpl->rpcClient->call("getLeonCssHeapUsage").as<MemoryInfo>();
1166 }
1167 
1169  return pimpl->rpcClient->call("getLeonMssHeapUsage").as<MemoryInfo>();
1170 }
1171 
1173  return pimpl->rpcClient->call("getChipTemperature").as<ChipTemperature>();
1174 }
1175 
1177  return pimpl->rpcClient->call("getLeonCssCpuUsage").as<CpuUsage>();
1178 }
1179 
1181  return pimpl->rpcClient->call("getLeonMssCpuUsage").as<CpuUsage>();
1182 }
1183 
1185  return pimpl->rpcClient->call("getUsbSpeed").as<UsbSpeed>();
1186 }
1187 
1189  return bootloaderVersion;
1190 }
1191 
1193  return pimpl->rpcClient->call("isPipelineRunning").as<bool>();
1194 }
1195 
1197  pimpl->rpcClient->call("setLogLevel", level);
1198 }
1199 
1201  return pimpl->rpcClient->call("getLogLevel").as<LogLevel>();
1202 }
1203 
1204 void DeviceBase::setXLinkChunkSize(int sizeBytes) {
1205  pimpl->rpcClient->call("setXLinkChunkSize", sizeBytes);
1206 }
1207 
1209  return pimpl->rpcClient->call("getXLinkChunkSize").as<int>();
1210 }
1211 
1212 void DeviceBase::setXLinkRateLimit(int maxRateBytesPerSecond, int burstSize, int waitUs) {
1213  pimpl->rpcClient->call("setXLinkRateLimit", maxRateBytesPerSecond, burstSize, waitUs);
1214 }
1215 
1217  return deviceInfo;
1218 }
1219 
1223  return utility::parseProductName(eeprom, eepromFactory);
1224 }
1225 
1229  return utility::parseDeviceName(eeprom, eepromFactory);
1230 }
1231 
1233  pimpl->setLogLevel(level);
1234 }
1235 
1237  return pimpl->getLogLevel();
1238 }
1239 
1241  return pimpl->rpcClient->call("setIrLaserDotProjectorBrightness", mA, mask, false);
1242 }
1243 
1244 bool DeviceBase::setIrLaserDotProjectorIntensity(float intensity, int mask) {
1245  return pimpl->rpcClient->call("setIrLaserDotProjectorBrightness", intensity, mask, true);
1246 }
1247 
1248 bool DeviceBase::setIrFloodLightBrightness(float mA, int mask) {
1249  return pimpl->rpcClient->call("setIrFloodLightBrightness", mA, mask, false);
1250 }
1251 
1252 bool DeviceBase::setIrFloodLightIntensity(float intensity, int mask) {
1253  return pimpl->rpcClient->call("setIrFloodLightBrightness", intensity, mask, true);
1254 }
1255 
1256 std::vector<std::tuple<std::string, int, int>> DeviceBase::getIrDrivers() {
1257  return pimpl->rpcClient->call("getIrDrivers");
1258 }
1259 
1261  return pimpl->rpcClient->call("getCrashDump", clearCrashDump).as<dai::CrashDump>();
1262 }
1263 
1265  return pimpl->rpcClient->call("hasCrashDump").as<bool>();
1266 }
1267 
1269  return connection->getProfilingData();
1270 }
1271 
1272 int DeviceBase::addLogCallback(std::function<void(LogMessage)> callback) {
1273  // Lock first
1274  std::unique_lock<std::mutex> l(logCallbackMapMtx);
1275 
1276  // Get unique id
1277  int id = uniqueCallbackId++;
1278 
1279  // assign callback
1280  logCallbackMap[id] = callback;
1281 
1282  // return id assigned to the callback
1283  return id;
1284 }
1285 
1286 bool DeviceBase::removeLogCallback(int callbackId) {
1287  // Lock first
1288  std::unique_lock<std::mutex> l(logCallbackMapMtx);
1289 
1290  // If callback with id 'callbackId' doesn't exists, return false
1291  if(logCallbackMap.count(callbackId) == 0) return false;
1292 
1293  // Otherwise erase and return true
1294  logCallbackMap.erase(callbackId);
1295  return true;
1296 }
1297 
1298 void DeviceBase::setTimesync(std::chrono::milliseconds period, int numSamples, bool random) {
1299  if(period < std::chrono::milliseconds(10)) {
1300  throw std::invalid_argument("Period must be greater or equal than 10ms");
1301  }
1302 
1303  using namespace std::chrono;
1304  pimpl->rpcClient->call("setTimesync", duration_cast<milliseconds>(period).count(), numSamples, random);
1305 }
1306 
1307 void DeviceBase::setTimesync(bool enable) {
1308  if(enable) {
1310  } else {
1311  setTimesync(std::chrono::milliseconds(1000), 0, false);
1312  }
1313 }
1314 
1316  pimpl->rpcClient->call("setSystemInformationLoggingRate", rateHz);
1317 }
1318 
1320  return pimpl->rpcClient->call("getSystemInformationLoggingRate").as<float>();
1321 }
1322 
1324  return pimpl->rpcClient->call("isEepromAvailable").as<bool>();
1325 }
1326 
1327 bool DeviceBase::flashCalibration(CalibrationHandler calibrationDataHandler) {
1328  try {
1329  flashCalibration2(calibrationDataHandler);
1330  } catch(const EepromError&) {
1331  return false;
1332  }
1333  return true;
1334 }
1335 
1337  bool factoryPermissions = false;
1338  bool protectedPermissions = false;
1339  getFlashingPermissions(factoryPermissions, protectedPermissions);
1340  pimpl->logger.debug("Flashing calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions);
1341 
1342  /* if(!calibrationDataHandler.validateCameraArray()) {
1343  throw std::runtime_error("Failed to validate the extrinsics connection. Enable debug mode for more information.");
1344  } */
1345 
1346  bool success;
1347  std::string errorMsg;
1348  std::tie(success, errorMsg) = pimpl->rpcClient->call("storeToEeprom", calibrationDataHandler.getEepromData(), factoryPermissions, protectedPermissions)
1349  .as<std::tuple<bool, std::string>>();
1350 
1351  if(!success) {
1352  throw std::runtime_error(errorMsg);
1353  }
1354 }
1355 
1356 void DeviceBase::setCalibration(CalibrationHandler calibrationDataHandler) {
1357  bool success;
1358  std::string errorMsg;
1359  std::tie(success, errorMsg) = pimpl->rpcClient->call("setCalibration", calibrationDataHandler.getEepromData()).as<std::tuple<bool, std::string>>();
1360  if(!success) {
1361  throw std::runtime_error(errorMsg);
1362  }
1363 }
1364 
1366  bool success;
1367  std::string errorMsg;
1368  dai::EepromData eepromData;
1369  std::tie(success, errorMsg, eepromData) = pimpl->rpcClient->call("getCalibration").as<std::tuple<bool, std::string, dai::EepromData>>();
1370  if(!success) {
1371  throw EepromError(errorMsg);
1372  }
1373  return CalibrationHandler(eepromData);
1374 }
1375 
1377  dai::EepromData eepromData{};
1378  try {
1379  return readCalibration2();
1380  } catch(const EepromError&) {
1381  // ignore - use default
1382  }
1383  return CalibrationHandler(eepromData);
1384 }
1386  bool success;
1387  std::string errorMsg;
1388  dai::EepromData eepromData;
1389  std::tie(success, errorMsg, eepromData) = pimpl->rpcClient->call("readFromEeprom").as<std::tuple<bool, std::string, dai::EepromData>>();
1390  if(!success) {
1391  throw EepromError(errorMsg);
1392  }
1393  return CalibrationHandler(eepromData);
1394 }
1395 
1397  return readCalibration();
1398 }
1399 
1401  bool factoryPermissions = false;
1402  bool protectedPermissions = false;
1403  getFlashingPermissions(factoryPermissions, protectedPermissions);
1404  pimpl->logger.debug("Flashing factory calibration. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions);
1405 
1406  if(!factoryPermissions) {
1407  throw std::runtime_error("Calling factory API is not allowed in current configuration");
1408  }
1409 
1410  /* if(!calibrationDataHandler.validateCameraArray()) {
1411  throw std::runtime_error("Failed to validate the extrinsics connection. Enable debug mode for more information.");
1412  } */
1413 
1414  bool success;
1415  std::string errorMsg;
1416  std::tie(success, errorMsg) =
1417  pimpl->rpcClient->call("storeToEepromFactory", calibrationDataHandler.getEepromData(), factoryPermissions, protectedPermissions)
1418  .as<std::tuple<bool, std::string>>();
1419  if(!success) {
1420  throw EepromError(errorMsg);
1421  }
1422 }
1423 
1425  bool success;
1426  std::string errorMsg;
1427  dai::EepromData eepromData;
1428  std::tie(success, errorMsg, eepromData) = pimpl->rpcClient->call("readFromEepromFactory").as<std::tuple<bool, std::string, dai::EepromData>>();
1429  if(!success) {
1430  throw EepromError(errorMsg);
1431  }
1432  return CalibrationHandler(eepromData);
1433 }
1435  dai::EepromData eepromData{};
1436  try {
1437  return readFactoryCalibration();
1438  } catch(const EepromError&) {
1439  // ignore - use default
1440  }
1441  return CalibrationHandler(eepromData);
1442 }
1443 
1445  bool success;
1446  std::string errorMsg;
1447  std::tie(success, errorMsg) = pimpl->rpcClient->call("eepromFactoryReset").as<std::tuple<bool, std::string>>();
1448  if(!success) {
1449  throw EepromError(errorMsg);
1450  }
1451 }
1452 
1453 std::vector<std::uint8_t> DeviceBase::readCalibrationRaw() {
1454  bool success;
1455  std::string errorMsg;
1456  std::vector<uint8_t> eepromDataRaw;
1457  std::tie(success, errorMsg, eepromDataRaw) = pimpl->rpcClient->call("readFromEepromRaw").as<std::tuple<bool, std::string, std::vector<uint8_t>>>();
1458  if(!success) {
1459  throw EepromError(errorMsg);
1460  }
1461  return eepromDataRaw;
1462 }
1463 
1464 std::vector<std::uint8_t> DeviceBase::readFactoryCalibrationRaw() {
1465  bool success;
1466  std::string errorMsg;
1467  std::vector<uint8_t> eepromDataRaw;
1468  std::tie(success, errorMsg, eepromDataRaw) = pimpl->rpcClient->call("readFromEepromFactoryRaw").as<std::tuple<bool, std::string, std::vector<uint8_t>>>();
1469  if(!success) {
1470  throw EepromError(errorMsg);
1471  }
1472  return eepromDataRaw;
1473 }
1474 
1476  bool factoryPermissions = false;
1477  bool protectedPermissions = false;
1478  getFlashingPermissions(factoryPermissions, protectedPermissions);
1479  pimpl->logger.debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions);
1480 
1481  if(!protectedPermissions) {
1482  throw std::runtime_error("Calling EEPROM clear API is not allowed in current configuration");
1483  }
1484 
1485  bool success;
1486  std::string errorMsg;
1487  std::tie(success, errorMsg) = pimpl->rpcClient->call("eepromClear", protectedPermissions, factoryPermissions).as<std::tuple<bool, std::string>>();
1488  if(!success) {
1489  throw EepromError(errorMsg);
1490  }
1491 }
1492 
1494  bool factoryPermissions = false;
1495  bool protectedPermissions = false;
1496  getFlashingPermissions(factoryPermissions, protectedPermissions);
1497  pimpl->logger.debug("Clearing User EEPROM contents. Factory permissions {}, Protected permissions {}", factoryPermissions, protectedPermissions);
1498 
1499  if(!protectedPermissions || !factoryPermissions) {
1500  throw std::runtime_error("Calling factory EEPROM clear API is not allowed in current configuration");
1501  }
1502 
1503  bool success;
1504  std::string errorMsg;
1505  std::tie(success, errorMsg) = pimpl->rpcClient->call("eepromFactoryClear", protectedPermissions, factoryPermissions).as<std::tuple<bool, std::string>>();
1506  if(!success) {
1507  throw EepromError(errorMsg);
1508  }
1509 }
1510 
1512  // Deprecated
1513  return true;
1514 }
1515 
1516 bool DeviceBase::startPipeline(const Pipeline& pipeline) {
1517  // first check if pipeline is not already running
1518  if(isPipelineRunning()) {
1519  throw std::runtime_error("Pipeline is already running");
1520  }
1521 
1522  return startPipelineImpl(pipeline);
1523 }
1524 
1526  // Check openvino version
1527  if(!pipeline.isOpenVINOVersionCompatible(config.version)) {
1528  throw std::runtime_error("Device booted with different OpenVINO version that pipeline requires");
1529  }
1530 
1531  // Serialize the pipeline
1532  PipelineSchema schema;
1533  Assets assets;
1534  std::vector<std::uint8_t> assetStorage;
1535  pipeline.serialize(schema, assets, assetStorage);
1536 
1537  // if debug or lower
1539  nlohmann::json jSchema = schema;
1540  pimpl->logger.debug("Schema dump: {}", jSchema.dump());
1541  nlohmann::json jAssets = assets;
1542  pimpl->logger.debug("Asset map dump: {}", jAssets.dump());
1543  }
1544 
1545  // Load pipelineDesc, assets, and asset storage
1546  pimpl->rpcClient->call("setPipelineSchema", schema);
1547 
1548  // Transfer storage != empty
1549  if(!assetStorage.empty()) {
1550  pimpl->rpcClient->call("setAssets", assets);
1551 
1552  // Transfer the whole assetStorage in a separate thread
1553  const std::string streamAssetStorage = "__stream_asset_storage";
1554  std::thread t1([this, &streamAssetStorage, &assetStorage]() {
1555  XLinkStream stream(connection, streamAssetStorage, device::XLINK_USB_BUFFER_MAX_SIZE);
1556  int64_t offset = 0;
1557  do {
1558  int64_t toTransfer = std::min(static_cast<int64_t>(device::XLINK_USB_BUFFER_MAX_SIZE), static_cast<int64_t>(assetStorage.size() - offset));
1559  stream.write(&assetStorage[offset], toTransfer);
1560  offset += toTransfer;
1561  } while(offset < static_cast<int64_t>(assetStorage.size()));
1562  });
1563 
1564  pimpl->rpcClient->call("readAssetStorageFromXLink", streamAssetStorage, assetStorage.size());
1565  t1.join();
1566  }
1567 
1568  // print assets on device side for test
1569  pimpl->rpcClient->call("printAssets");
1570 
1571  // Log the pipeline
1573  this->pipelineSchema = schema; // Save the schema so it can be passed alongside the crashdump
1574 
1575  // Build and start the pipeline
1576  bool success = false;
1577  std::string errorMsg;
1578  std::tie(success, errorMsg) = pimpl->rpcClient->call("buildPipeline").as<std::tuple<bool, std::string>>();
1579  if(success) {
1580  pimpl->rpcClient->call("startPipeline");
1581  } else {
1582  throw std::runtime_error(errorMsg);
1583  return false;
1584  }
1585 
1586  return true;
1587 }
1588 } // namespace dai
LogMessage.hpp
dai::DeviceBase::watchdogRunning
std::atomic< bool > watchdogRunning
Definition: DeviceBase.hpp:984
dai::DeviceBase::getLeonCssCpuUsage
CpuUsage getLeonCssCpuUsage()
Definition: DeviceBase.cpp:1176
dai::DeviceBase::startPipeline
bool startPipeline()
Definition: DeviceBase.cpp:1511
dai::XLinkConnection::getAllConnectedDevices
static std::vector< DeviceInfo > getAllConnectedDevices(XLinkDeviceState_t state=X_LINK_ANY_STATE, bool skipInvalidDevices=true, XLinkPlatform_t platform=X_LINK_MYRIAD_X)
Definition: XLinkConnection.cpp:113
dai::XLinkStream::read
std::vector< std::uint8_t > read()
Definition: XLinkStream.cpp:113
dai::DeviceBase::isClosed
bool isClosed() const
Definition: DeviceBase.cpp:627
dai::DeviceBase::getCalibration
CalibrationHandler getCalibration()
Definition: DeviceBase.cpp:1365
dai::DeviceBase::flashEepromClear
void flashEepromClear()
Definition: DeviceBase.cpp:1475
dai::ProfilingData::numBytesRead
long long numBytesRead
Definition: ProfilingData.hpp:7
dai::DeviceBase::setIrLaserDotProjectorBrightness
bool setIrLaserDotProjectorBrightness(float mA, int mask=-1)
Definition: DeviceBase.cpp:1240
dai::DeviceBase::getDeviceInfo
DeviceInfo getDeviceInfo() const
Definition: DeviceBase.cpp:1216
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
dai::DeviceBase::DEFAULT_TIMESYNC_RANDOM
static constexpr bool DEFAULT_TIMESYNC_RANDOM
Default Timesync packet interval randomness.
Definition: DeviceBase.hpp:65
Pipeline.hpp
dai::DeviceBase::timesyncRunning
std::atomic< bool > timesyncRunning
Definition: DeviceBase.hpp:988
dai::LogLevel::TRACE
@ TRACE
dai::DeviceBase::init2
void init2(Config cfg, const dai::Path &pathToMvcmd, tl::optional< const Pipeline & > pipeline)
Definition: DeviceBase.cpp:670
dai::DeviceBase::Impl::setLogLevel
void setLogLevel(LogLevel level)
Definition: DeviceBase.cpp:304
dai::UsbSpeed
UsbSpeed
Definition: shared/depthai-shared/include/depthai-shared/common/UsbSpeed.hpp:12
dai::EepromError
Definition: EepromError.hpp:7
dai::DeviceBootloader::bootUsbRomBootloader
void bootUsbRomBootloader()
Definition: DeviceBootloader.cpp:1384
dai::DeviceBase::close
void close()
Definition: DeviceBase.cpp:516
dai::DeviceBootloader
Definition: DeviceBootloader.hpp:29
dai::DeviceBase::getLogLevel
LogLevel getLogLevel()
Definition: DeviceBase.cpp:1200
dai::DeviceBase::~DeviceBase
virtual ~DeviceBase()
Definition: DeviceBase.cpp:632
dai::DeviceBase::watchdogThread
std::thread watchdogThread
Definition: DeviceBase.hpp:983
dai::DeviceInfo
Definition: XLinkConnection.hpp:27
dai::XLinkConnection::getFirstDevice
static std::tuple< bool, DeviceInfo > getFirstDevice(XLinkDeviceState_t state=X_LINK_ANY_STATE, bool skipInvalidDevices=true)
Definition: XLinkConnection.cpp:160
dai::utility::parseProductName
std::string parseProductName(EepromData eeprom, EepromData eepromFactory)
Parses product name from given EepromData combination.
Definition: EepromDataParser.cpp:22
dai::DeviceBase::getDeviceByMxId
static std::tuple< bool, DeviceInfo > getDeviceByMxId(std::string mxId)
Definition: DeviceBase.cpp:243
dai::DeviceBase::setIrFloodLightBrightness
bool setIrFloodLightBrightness(float mA, int mask=-1)
Definition: DeviceBase.cpp:1248
dai::MAGIC_FACTORY_FLASHING_VALUE
const std::string MAGIC_FACTORY_FLASHING_VALUE
Definition: DeviceBase.cpp:48
dai::DeviceBase::tryGetDevice
void tryGetDevice()
Definition: DeviceBase.cpp:320
dai::DeviceBase::getGlobalProfilingData
static ProfilingData getGlobalProfilingData()
Definition: DeviceBase.cpp:263
DeviceBase.hpp
dai::DeviceInfo::toString
std::string toString() const
Definition: XLinkConnection.cpp:79
dai::DeviceBase::Config::board
BoardConfig board
Definition: DeviceBase.hpp:74
dai::OpenVINO::Version
Version
OpenVINO Version supported version information.
Definition: OpenVINO.hpp:20
dai::DeviceBase::lastWatchdogPingTimeMtx
std::mutex lastWatchdogPingTimeMtx
Definition: DeviceBase.hpp:1000
Environment.hpp
dai::DeviceBase::getLeonMssHeapUsage
MemoryInfo getLeonMssHeapUsage()
Definition: DeviceBase.cpp:1168
Resources.hpp
dai::DeviceBase::getIrDrivers
std::vector< std::tuple< std::string, int, int > > getIrDrivers()
Definition: DeviceBase.cpp:1256
dai::logger::get_level
spdlog::level::level_enum get_level()
Definition: Logging.hpp:48
dai::logger::critical
void critical(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:96
dai::DeviceBase::profilingRunning
std::atomic< bool > profilingRunning
Definition: DeviceBase.hpp:996
dai::PipelineSchema
Definition: PipelineSchema.hpp:13
dai::DeviceBase::flashFactoryCalibration
void flashFactoryCalibration(CalibrationHandler calibrationHandler)
Definition: DeviceBase.cpp:1400
dai::DeviceBase::readFactoryCalibration
CalibrationHandler readFactoryCalibration()
Definition: DeviceBase.cpp:1424
dai::DeviceBase::readCalibrationOrDefault
CalibrationHandler readCalibrationOrDefault()
Definition: DeviceBase.cpp:1396
dai::LOG_DEFAULT_PATTERN
static constexpr const char * LOG_DEFAULT_PATTERN
Definition: LogConstants.hpp:5
dai::logger::info
void info(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:78
dai::logCollection::logCrashDump
void logCrashDump(const tl::optional< PipelineSchema > &pipelineSchema, const CrashDump &crashDump, const dai::DeviceInfo &deviceInfo)
Definition: LogCollection.cpp:178
nanorpc::version::core::protocol
std::integral_constant< std::uint32_t, 1 > protocol
Definition: core.h:22
dai::StereoPair
Definition: shared/depthai-shared/include/depthai-shared/common/StereoPair.hpp:11
XLinkConstants.hpp
dai::ProfilingData::numBytesWritten
long long numBytesWritten
Definition: ProfilingData.hpp:6
dai::DeviceBase::DEFAULT_SEARCH_TIME
static constexpr std::chrono::seconds DEFAULT_SEARCH_TIME
Default search time for constructors which discover devices.
Definition: DeviceBase.hpp:55
dai::DeviceBase::loggingThread
std::thread loggingThread
Definition: DeviceBase.hpp:991
dai::CalibrationHandler::getCameraTranslationVector
std::vector< float > getCameraTranslationVector(CameraBoardSocket srcCamera, CameraBoardSocket dstCamera, bool useSpecTranslation=true) const
Definition: CalibrationHandler.cpp:390
dai::XLinkStream
Definition: XLinkStream.hpp:37
Version
dai::DeviceBootloader::Version Version
Definition: bootloader_version_test.cpp:9
dai::DeviceBase::setCalibration
void setCalibration(CalibrationHandler calibrationDataHandler)
Definition: DeviceBase.cpp:1356
dai::DeviceBase::setLogLevel
void setLogLevel(LogLevel level)
Definition: DeviceBase.cpp:1196
dai::LogLevel::INFO
@ INFO
dai::DeviceBase::DEFAULT_TIMESYNC_NUM_SAMPLES
static constexpr int DEFAULT_TIMESYNC_NUM_SAMPLES
Default Timesync number of samples per sync.
Definition: DeviceBase.hpp:63
dai::Version
Version structure.
Definition: Version.hpp:8
dai::DeviceBase::init
void init(OpenVINO::Version version)
Definition: DeviceBase.cpp:422
dai::logger::debug
void debug(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:72
dai::DeviceInfo::state
XLinkDeviceState_t state
Definition: XLinkConnection.hpp:42
dai::DeviceBase::getLeonCssHeapUsage
MemoryInfo getLeonCssHeapUsage()
Definition: DeviceBase.cpp:1164
dai::DeviceBase::loggingRunning
std::atomic< bool > loggingRunning
Definition: DeviceBase.hpp:992
dai::DeviceBase::Impl::rpcMutex
std::mutex rpcMutex
Definition: DeviceBase.cpp:291
dai::logger::warn
void warn(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:84
dai::DeviceBase::flashCalibration2
void flashCalibration2(CalibrationHandler calibrationDataHandler)
Definition: DeviceBase.cpp:1336
dai::logger::log
void log(spdlog::source_loc source, spdlog::level::level_enum lvl, const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:54
dai::DeviceLogger
Definition: DeviceLogger.hpp:7
dai::utility::serialize
bool serialize(const T &obj, std::vector< std::uint8_t > &data)
Definition: Serialization.hpp:38
dai::Resources::getInstance
static Resources & getInstance()
Definition: Resources.cpp:248
dai::DeviceBase::setLogOutputLevel
void setLogOutputLevel(LogLevel level)
Definition: DeviceBase.cpp:1232
dai::ProfilingData
Definition: ProfilingData.hpp:5
dai::CrashDump
Definition: CrashDump.hpp:14
dai::DeviceBase::Impl
Definition: DeviceBase.cpp:281
DAI_SPAN_NAMESPACE_NAME::detail::data
constexpr auto data(C &c) -> decltype(c.data())
Definition: span.hpp:177
dai::LogLevel::CRITICAL
@ CRITICAL
dai::DeviceBase::pipelineSchema
tl::optional< PipelineSchema > pipelineSchema
Definition: DeviceBase.hpp:1018
dai::BoardConfig::nonExclusiveMode
bool nonExclusiveMode
Definition: BoardConfig.hpp:113
dai::DeviceBase::profilingThread
std::thread profilingThread
Definition: DeviceBase.hpp:995
dai::DeviceBase::getSystemInformationLoggingRate
float getSystemInformationLoggingRate()
Definition: DeviceBase.cpp:1319
EepromDataParser.hpp
dai::DeviceBase::getConnectedCameraFeatures
std::vector< CameraFeatures > getConnectedCameraFeatures()
Definition: DeviceBase.cpp:1109
nanorpc::core::type::buffer
std::vector< std::uint8_t > buffer
Definition: type.h:28
PimplImpl.hpp
Bootloader.hpp
dai::DeviceBase::config
Config config
Definition: DeviceBase.hpp:1012
dai::utility::getEnv
std::string getEnv(const std::string &var)
Definition: Environment.cpp:18
dai::DeviceBase::readCalibrationRaw
std::vector< std::uint8_t > readCalibrationRaw()
Definition: DeviceBase.cpp:1453
dai::DeviceBase::readFactoryCalibrationRaw
std::vector< std::uint8_t > readFactoryCalibrationRaw()
Definition: DeviceBase.cpp:1464
dai::DeviceBase::getIMUFirmwareVersion
dai::Version getIMUFirmwareVersion()
Definition: DeviceBase.cpp:1125
dai::DeviceBase::getProductName
std::string getProductName()
Definition: DeviceBase.cpp:1220
dai::DeviceBase::lastWatchdogPingTime
std::chrono::steady_clock::time_point lastWatchdogPingTime
Definition: DeviceBase.hpp:1001
dai::DeviceBase::getCmxMemoryUsage
MemoryInfo getCmxMemoryUsage()
Definition: DeviceBase.cpp:1160
dai::CpuUsage
Definition: CpuUsage.hpp:12
dai::DeviceBase::readFactoryCalibrationOrDefault
CalibrationHandler readFactoryCalibrationOrDefault()
Definition: DeviceBase.cpp:1434
dai::DeviceBase::getEmbeddedIMUFirmwareVersion
dai::Version getEmbeddedIMUFirmwareVersion()
Definition: DeviceBase.cpp:1136
RawImgFrame.hpp
dai::DeviceBase::pimpl
Pimpl< Impl > pimpl
Definition: DeviceBase.hpp:1008
dai::DeviceBase::getConnectionInterfaces
std::vector< ConnectionInterface > getConnectionInterfaces()
Definition: DeviceBase.cpp:1105
dai::Pipeline::serialize
void serialize(PipelineSchema &schema, Assets &assets, std::vector< std::uint8_t > &assetStorage) const
Definition: Pipeline.hpp:130
dai::DeviceBase::getConnectedIMU
std::string getConnectedIMU()
Definition: DeviceBase.cpp:1121
dai::utility::deserialize
bool deserialize(const std::uint8_t *data, std::size_t size, T &obj)
Definition: Serialization.hpp:44
dai::DeviceBase::getXLinkChunkSize
int getXLinkChunkSize()
Definition: DeviceBase.cpp:1208
dai::DeviceBootloader::getVersion
Version getVersion() const
Definition: DeviceBootloader.cpp:599
Initialization.hpp
dai::MAGIC_PROTECTED_FLASHING_VALUE
const std::string MAGIC_PROTECTED_FLASHING_VALUE
Definition: DeviceBase.cpp:47
dai::device::XLINK_USB_BUFFER_MAX_SIZE
constexpr static std::uint32_t XLINK_USB_BUFFER_MAX_SIZE
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:17
dai::initialize
bool initialize()
Definition: Initialization.cpp:53
dai::DeviceBase::timesyncThread
std::thread timesyncThread
Definition: DeviceBase.hpp:987
dai::DeviceBase::setIrFloodLightIntensity
bool setIrFloodLightIntensity(float intensity, int mask=-1)
Definition: DeviceBase.cpp:1252
dai::DeviceBase::readCalibration
CalibrationHandler readCalibration()
Definition: DeviceBase.cpp:1376
dai::DeviceInfo::name
std::string name
Definition: XLinkConnection.hpp:40
dai::DeviceBase::Impl::rpcStream
std::shared_ptr< XLinkStream > rpcStream
Definition: DeviceBase.cpp:292
dai::XLinkConnection::getGlobalProfilingData
static ProfilingData getGlobalProfilingData()
Definition: XLinkConnection.cpp:508
dai::device::XLINK_CHANNEL_WATCHDOG
constexpr static const char * XLINK_CHANNEL_WATCHDOG
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:14
dai::DeviceBase::Config::logLevel
tl::optional< LogLevel > logLevel
Definition: DeviceBase.hpp:77
dai::DeviceBase::getDeviceName
std::string getDeviceName()
Definition: DeviceBase.cpp:1226
dai::DeviceBase::startPipelineImpl
virtual bool startPipelineImpl(const Pipeline &pipeline)
Definition: DeviceBase.cpp:1525
dai::device::XLINK_CHANNEL_TIMESYNC
constexpr static const char * XLINK_CHANNEL_TIMESYNC
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:12
dai::DeviceBase::closedMtx
std::mutex closedMtx
Definition: DeviceBase.hpp:1004
dai::MAGIC_FACTORY_PROTECTED_FLASHING_VALUE
const std::string MAGIC_FACTORY_PROTECTED_FLASHING_VALUE
Definition: DeviceBase.cpp:49
dai::device::XLINK_USB_WATCHDOG_TIMEOUT
constexpr static const std::chrono::milliseconds XLINK_USB_WATCHDOG_TIMEOUT
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:20
dai::DeviceBase::getEmbeddedDeviceBinary
static std::vector< std::uint8_t > getEmbeddedDeviceBinary(bool usb2Mode, OpenVINO::Version version=OpenVINO::VERSION_UNIVERSAL)
Definition: DeviceBase.cpp:255
dai::LogMessage
Definition: LogMessage.hpp:13
dai::DeviceBase::setIrLaserDotProjectorIntensity
bool setIrLaserDotProjectorIntensity(float intensity, int mask=-1)
Definition: DeviceBase.cpp:1244
dai::Resources::getDeviceFirmware
std::vector< std::uint8_t > getDeviceFirmware(bool usb2Mode, OpenVINO::Version version=OpenVINO::VERSION_UNIVERSAL) const
Definition: Resources.cpp:371
dai::DeviceBase::getBootloaderVersion
tl::optional< Version > getBootloaderVersion()
Definition: DeviceBase.cpp:1188
dai::DeviceBase::closeImpl
virtual void closeImpl()
Definition: DeviceBase.cpp:536
dai::DeviceBase::startIMUFirmwareUpdate
bool startIMUFirmwareUpdate(bool forceUpdate=false)
Definition: DeviceBase.cpp:1147
dai::device::XLINK_TCP_WATCHDOG_TIMEOUT
constexpr static const std::chrono::milliseconds XLINK_TCP_WATCHDOG_TIMEOUT
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:21
dai::BoardConfig::USB::maxSpeed
UsbSpeed maxSpeed
Definition: BoardConfig.hpp:28
dai::Pipeline::getDeviceConfig
Device::Config getDeviceConfig() const
Get device configuration needed for this pipeline.
Definition: Pipeline.hpp:308
dai::logCollection::logPipeline
void logPipeline(const PipelineSchema &pipelineSchema, const dai::DeviceInfo &deviceInfo)
Definition: LogCollection.cpp:126
Assets.hpp
dai::LogLevel
LogLevel
Definition: LogLevel.hpp:12
nanorpc::core::type::id
std::uint64_t id
Definition: type.h:27
dai::DeviceBase::flashCalibration
bool flashCalibration(CalibrationHandler calibrationDataHandler)
Definition: DeviceBase.cpp:1327
XLinkIn.hpp
dai::DeviceBase::deviceInfo
DeviceInfo deviceInfo
Definition: DeviceBase.hpp:974
nanorpc::core::exception::to_string
std::string to_string(std::exception const &e)
Definition: exception.h:46
dai::Assets
Definition: Assets.hpp:22
dai::device::XLINK_CHANNEL_MAIN_RPC
constexpr static const char * XLINK_CHANNEL_MAIN_RPC
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:11
dai::LogLevel::OFF
@ OFF
Files.hpp
dai::DeviceBase::DEFAULT_TIMESYNC_PERIOD
static constexpr std::chrono::milliseconds DEFAULT_TIMESYNC_PERIOD
Default Timesync period.
Definition: DeviceBase.hpp:61
dai::CalibrationHandler
Definition: CalibrationHandler.hpp:24
dai::LogLevel::WARN
@ WARN
Serialization.hpp
dai::DeviceBase::connection
std::shared_ptr< XLinkConnection > connection
Definition: DeviceBase.hpp:924
dai::DeviceBase::setSystemInformationLoggingRate
void setSystemInformationLoggingRate(float rateHz)
Definition: DeviceBase.cpp:1315
LogCollection.hpp
CrashDump.hpp
dai::DeviceBase::DeviceBase
DeviceBase()
Definition: DeviceBase.cpp:353
dai::utility::parseDeviceName
std::string parseDeviceName(EepromData eeprom, EepromData eepromFactory)
Parses device name from given EepromData combination.
Definition: EepromDataParser.cpp:46
dai::OpenVINO
Support for basic OpenVINO related actions like version identification of neural network blobs,...
Definition: OpenVINO.hpp:17
dai::DeviceBase::logCallbackMapMtx
std::mutex logCallbackMapMtx
Definition: DeviceBase.hpp:979
dai::DeviceBase::getCameraSensorNames
std::unordered_map< CameraBoardSocket, std::string > getCameraSensorNames()
Definition: DeviceBase.cpp:1117
dai::DeviceBase::closed
bool closed
Definition: DeviceBase.hpp:1005
dai::spdlogLevelToLogLevel
static LogLevel spdlogLevelToLogLevel(spdlog::level::level_enum level, LogLevel defaultValue=LogLevel::OFF)
Definition: DeviceBase.cpp:71
dai::DeviceBase::readCalibration2
CalibrationHandler readCalibration2()
Definition: DeviceBase.cpp:1385
dai::LogLevel::ERR
@ ERR
dai::device::XLINK_CHANNEL_LOG
constexpr static const char * XLINK_CHANNEL_LOG
Definition: depthai-shared/include/depthai-shared/xlink/XLinkConstants.hpp:13
dai::DeviceBase::tryStartPipeline
void tryStartPipeline(const Pipeline &pipeline)
a safe way to start a pipeline, which is closed if any exception occurs
Definition: DeviceBase.cpp:636
dai::DeviceBase::getStereoPairs
std::vector< StereoPair > getStereoPairs()
Definition: DeviceBase.cpp:1113
dai::DeviceInfo::getMxId
std::string getMxId() const
Definition: XLinkConnection.cpp:75
dai::DeviceBase::getProfilingData
ProfilingData getProfilingData()
Definition: DeviceBase.cpp:1268
dai::Pipeline::isOpenVINOVersionCompatible
bool isOpenVINOVersionCompatible(OpenVINO::Version version) const
Checks whether a given OpenVINO version is compatible with the pipeline.
Definition: Pipeline.hpp:293
dai::XLinkStream::write
void write(const void *data, std::size_t size)
Definition: XLinkStream.cpp:86
dai::DeviceBase::Config::outputLogLevel
tl::optional< LogLevel > outputLogLevel
Definition: DeviceBase.hpp:76
dai::DeviceBase::Config::version
OpenVINO::Version version
Definition: DeviceBase.hpp:73
dai::DeviceBase::factoryResetCalibration
void factoryResetCalibration()
Definition: DeviceBase.cpp:1444
dai::DeviceBase
Definition: DeviceBase.hpp:50
dai::DeviceBase::getUsbSpeed
UsbSpeed getUsbSpeed()
Definition: DeviceBase.cpp:1184
dai::DeviceBase::getAllAvailableDevices
static std::vector< DeviceInfo > getAllAvailableDevices()
Definition: DeviceBase.cpp:228
tl::optional
Definition: 3rdparty/tl/optional.hpp:120
dai::DeviceBase::getLogOutputLevel
LogLevel getLogOutputLevel()
Definition: DeviceBase.cpp:1236
dai::DeviceBase::setXLinkChunkSize
void setXLinkChunkSize(int sizeBytes)
Definition: DeviceBase.cpp:1204
std
Definition: Node.hpp:366
dai::DeviceBase::getLeonMssCpuUsage
CpuUsage getLeonMssCpuUsage()
Definition: DeviceBase.cpp:1180
dai::logLevelToSpdlogLevel
static spdlog::level::level_enum logLevelToSpdlogLevel(LogLevel level, spdlog::level::level_enum defaultValue=spdlog::level::off)
Definition: DeviceBase.cpp:96
dai::DeviceBase::setXLinkRateLimit
void setXLinkRateLimit(int maxRateBytesPerSecond, int burstSize=0, int waitUs=0)
Definition: DeviceBase.cpp:1212
dai::MemoryInfo
Definition: MemoryInfo.hpp:12
dai::OpenVINO::getVersionName
static std::string getVersionName(Version version)
Definition: OpenVINO.cpp:67
dai::DeviceBase::hasCrashDump
bool hasCrashDump()
Definition: DeviceBase.cpp:1264
dai::DeviceInfo::protocol
XLinkProtocol_t protocol
Definition: XLinkConnection.hpp:43
dai::DeviceBase::Config
Definition: DeviceBase.hpp:72
dai::DeviceInfo::getXLinkDeviceDesc
deviceDesc_t getXLinkDeviceDesc() const
Definition: XLinkConnection.cpp:56
dai::DeviceBase::DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ
static constexpr float DEFAULT_SYSTEM_INFORMATION_LOGGING_RATE_HZ
Default rate at which system information is logged.
Definition: DeviceBase.hpp:57
dai::BoardConfig::usb
USB usb
Definition: BoardConfig.hpp:32
dai::DeviceBase::getAllConnectedDevices
static std::vector< DeviceInfo > getAllConnectedDevices()
Definition: DeviceBase.cpp:238
XLinkOut.hpp
dai::DeviceBase::Impl::rpcClient
std::unique_ptr< nanorpc::core::client< nanorpc::packer::nlohmann_msgpack > > rpcClient
Definition: DeviceBase.cpp:293
dai::logger::trace
void trace(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:66
spdlog-fmt.hpp
dai::CalibrationHandler::getEepromData
dai::EepromData getEepromData() const
Definition: CalibrationHandler.cpp:200
EepromError.hpp
dai::DeviceBase::getMxId
std::string getMxId()
Definition: DeviceBase.cpp:1032
dai::XLinkConnection::getDeviceByMxId
static std::tuple< bool, DeviceInfo > getDeviceByMxId(std::string mxId, XLinkDeviceState_t state=X_LINK_ANY_STATE, bool skipInvalidDevice=true)
Definition: XLinkConnection.cpp:192
dai::DeviceBase::removeLogCallback
bool removeLogCallback(int callbackId)
Definition: DeviceBase.cpp:1286
dai::BoardConfig::watchdogInitialDelayMs
tl::optional< uint32_t > watchdogInitialDelayMs
Definition: BoardConfig.hpp:53
dai::DeviceBase::getConnectedCameras
std::vector< CameraBoardSocket > getConnectedCameras()
Definition: DeviceBase.cpp:1036
dai::DeviceBase::getAnyAvailableDevice
static std::tuple< bool, DeviceInfo > getAnyAvailableDevice()
Definition: DeviceBase.cpp:206
dai::DeviceBase::getFirstAvailableDevice
static std::tuple< bool, DeviceInfo > getFirstAvailableDevice(bool skipInvalidDevice=true)
Definition: DeviceBase.cpp:213
dai::DeviceBase::uniqueCallbackId
int uniqueCallbackId
Definition: DeviceBase.hpp:978
dai::ChipTemperature
Definition: ChipTemperature.hpp:12
dai::DeviceInfo::mxid
std::string mxid
Definition: XLinkConnection.hpp:41
dai::StereoPair::right
CameraBoardSocket right
Definition: shared/depthai-shared/include/depthai-shared/common/StereoPair.hpp:13
dai::DeviceBase::Config::nonExclusiveMode
bool nonExclusiveMode
Definition: DeviceBase.hpp:75
dai::DeviceBase::bootloaderVersion
tl::optional< Version > bootloaderVersion
Definition: DeviceBase.hpp:975
dai::DeviceBase::getAvailableStereoPairs
std::vector< StereoPair > getAvailableStereoPairs()
Definition: DeviceBase.cpp:1040
dai::Path
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
Definition: Path.hpp:27
dai::DeviceBase::getDefaultSearchTime
static std::chrono::milliseconds getDefaultSearchTime()
Get the Default Search Time for finding devices.
Definition: DeviceBase.cpp:124
dai::EepromData::cameraData
std::unordered_map< CameraBoardSocket, CameraInfo > cameraData
Definition: EepromData.hpp:25
dai::DeviceBase::addLogCallback
int addLogCallback(std::function< void(LogMessage)> callback)
Definition: DeviceBase.cpp:1272
Logging.hpp
dai::DeviceBase::monitorThread
std::thread monitorThread
Definition: DeviceBase.hpp:999
dai::DeviceBase::getChipTemperature
ChipTemperature getChipTemperature()
Definition: DeviceBase.cpp:1172
dai::LogLevel::DEBUG
@ DEBUG
LogConstants.hpp
tl::optional::value_or
constexpr T value_or(U &&u) const &
Returns the stored value if there is one, otherwise returns u
Definition: 3rdparty/tl/optional.hpp:1314
dai::DeviceBase::isPipelineRunning
bool isPipelineRunning()
Definition: DeviceBase.cpp:1192
nlohmann_msgpack.h
dai::DeviceBase::setTimesync
void setTimesync(std::chrono::milliseconds period, int numSamples, bool random)
Definition: DeviceBase.cpp:1298
dai::BoardConfig::logDevicePrints
tl::optional< bool > logDevicePrints
log device prints
Definition: BoardConfig.hpp:111
LogLevel.hpp
dai::DeviceBase::firmwarePath
dai::Path firmwarePath
Definition: DeviceBase.hpp:1014
dai
Definition: CameraExposureOffset.hpp:6
dai::EepromData
Definition: EepromData.hpp:19
dai::DeviceBase::isEepromAvailable
bool isEepromAvailable()
Definition: DeviceBase.cpp:1323
dai::DeviceBase::getIMUFirmwareUpdateStatus
std::tuple< bool, unsigned int > getIMUFirmwareUpdateStatus()
Definition: DeviceBase.cpp:1151
DeviceLogger.hpp
dai::BoardConfig::watchdogTimeoutMs
tl::optional< uint32_t > watchdogTimeoutMs
Watchdog config.
Definition: BoardConfig.hpp:52
dai::DeviceBootloader::bootMemory
void bootMemory(const std::vector< uint8_t > &fw)
Definition: DeviceBootloader.cpp:1364
dai::DeviceBase::Impl::getLogLevel
LogLevel getLogLevel()
Definition: DeviceBase.cpp:311
dai::DeviceBase::flashFactoryEepromClear
void flashFactoryEepromClear()
Definition: DeviceBase.cpp:1493
dai::DeviceBase::DEFAULT_USB_SPEED
static constexpr UsbSpeed DEFAULT_USB_SPEED
Default UsbSpeed for device connection.
Definition: DeviceBase.hpp:59
client.h
dai::getFlashingPermissions
static void getFlashingPermissions(bool &factoryPermissions, bool &protectedPermissions)
Definition: DeviceBase.cpp:54
dai::DeviceBase::getDdrMemoryUsage
MemoryInfo getDdrMemoryUsage()
Definition: DeviceBase.cpp:1156
dai::DeviceBase::dumpOnly
bool dumpOnly
Definition: DeviceBase.hpp:1015
dai::DeviceBase::Impl::setPattern
void setPattern(const std::string &pattern)
Definition: DeviceBase.cpp:300
dai::getCrashdumpTimeout
unsigned int getCrashdumpTimeout(XLinkProtocol_t protocol)
Definition: DeviceBase.cpp:524
dai::DEFAULT_CRASHDUMP_TIMEOUT
const unsigned int DEFAULT_CRASHDUMP_TIMEOUT
Definition: DeviceBase.cpp:51
dai::DeviceBase::logCallbackMap
std::unordered_map< int, std::function< void(LogMessage)> > logCallbackMap
Definition: DeviceBase.hpp:980
dai::DeviceBase::getCrashDump
dai::CrashDump getCrashDump(bool clearCrashDump=true)
Definition: DeviceBase.cpp:1260


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:19