DeviceBootloader.cpp
Go to the documentation of this file.
2 
3 // std
4 #include <fstream>
5 
6 // shared
15 
16 // project
17 #include "device/Device.hpp"
18 #include "pipeline/Pipeline.hpp"
19 #include "utility/Platform.hpp"
20 #include "utility/Resources.hpp"
21 #include "utility/spdlog-fmt.hpp"
22 
23 // libraries
24 #include "XLink/XLink.h"
25 #include "spdlog/fmt/chrono.h"
26 #include "spdlog/spdlog.h"
27 #include "utility/Logging.hpp"
28 #include "zlib.h"
29 
30 // Resource compiled assets (cmds)
31 #ifdef DEPTHAI_RESOURCE_COMPILED_BINARIES
32  #include "cmrc/cmrc.hpp"
33 CMRC_DECLARE(depthai);
34 #endif
35 
36 namespace dai {
37 
38 // Using
39 namespace Request = bootloader::request;
40 namespace Response = bootloader::response;
41 
42 // constants
44 
45 // static api
46 
47 // First tries to find UNBOOTED device, then BOOTLOADER device
48 std::tuple<bool, DeviceInfo> DeviceBootloader::getFirstAvailableDevice() {
49  // Get all connected devices
51  // Search order - first unbooted, then bootloader and last flash booted
52  for(auto searchState : {X_LINK_UNBOOTED, X_LINK_BOOTLOADER, X_LINK_FLASH_BOOTED}) {
53  for(const auto& device : devices) {
54  if(device.state == searchState) {
55  return {true, device};
56  }
57  }
58  }
59  return {false, {}};
60 }
61 
62 // Returns all devices which aren't already booted
63 std::vector<DeviceInfo> DeviceBootloader::getAllAvailableDevices() {
64  std::vector<DeviceInfo> availableDevices;
65  auto connectedDevices = XLinkConnection::getAllConnectedDevices();
66  for(const auto& d : connectedDevices) {
67  if(d.state != X_LINK_BOOTED) availableDevices.push_back(d);
68  }
69  return availableDevices;
70 }
71 
73  const Pipeline& pipeline, const dai::Path& pathToCmd, bool compress, std::string applicationName, bool checkChecksum) {
74  // Serialize the pipeline
75  PipelineSchema schema;
76  Assets assets;
77  std::vector<std::uint8_t> assetStorage;
78  pipeline.serialize(schema, assets, assetStorage);
79 
80  // Get DeviceConfig
81  DeviceBase::Config deviceConfig = pipeline.getDeviceConfig();
82 
83  // Prepare device firmware
84  std::vector<uint8_t> deviceFirmware = Resources::getInstance().getDeviceFirmware(deviceConfig, pathToCmd);
85  if(deviceFirmware.empty()) {
86  throw std::runtime_error("Error getting device firmware");
87  }
88 
89  // Serialize data
90  std::vector<uint8_t> pipelineBinary, assetsBinary;
91  utility::serialize(schema, pipelineBinary);
92  utility::serialize(assets, assetsBinary);
93 
94  // Prepare FW version buffer
95  std::string fwVersionBuffer{DEPTHAI_DEVICE_VERSION};
96 
97  // Prepare SBR structure
98  SBR sbr = {};
99  SBR_SECTION* lastSection = &sbr.sections[0];
100 
101  // Order of sections
102  SBR_SECTION* fwSection = lastSection++;
103  SBR_SECTION* pipelineSection = lastSection++;
104  SBR_SECTION* assetsSection = lastSection++;
105  SBR_SECTION* assetStorageSection = lastSection++;
106  SBR_SECTION* fwVersionSection = lastSection++;
107  SBR_SECTION* appNameSection = lastSection++;
108 
109  // Set to last section
110  lastSection = lastSection - 1;
111 
112  // Alignup for easier updating
113  auto getSectionAlignedOffset = [](long S) {
114  constexpr long SECTION_ALIGNMENT_SIZE = 1 * 1024 * 1024; // 1MiB for easier updating
115  return ((((S) + (SECTION_ALIGNMENT_SIZE)-1)) & ~((SECTION_ALIGNMENT_SIZE)-1));
116  };
117  // Alignup for easier updating
118  auto getSectionAlignedOffsetSmall = [](long S) {
119  constexpr long SECTION_ALIGNMENT_SIZE = 64 * 1024; // 64k for flash alignement
120  return ((((S) + (SECTION_ALIGNMENT_SIZE)-1)) & ~((SECTION_ALIGNMENT_SIZE)-1));
121  };
122 
123  // Should compress firmware?
124  if(compress) {
125  using namespace std::chrono;
126 
127  auto t1 = steady_clock::now();
128  auto compressBufferSize = compressBound(static_cast<decltype(compressBound(1))>(deviceFirmware.size()));
129  std::vector<uint8_t> compressBuffer(compressBufferSize);
130  // Chosen impirically
131  constexpr int COMPRESSION_LEVEL = 9;
132  if(compress2(compressBuffer.data(),
133  &compressBufferSize,
134  deviceFirmware.data(),
135  static_cast<decltype(compressBufferSize)>(deviceFirmware.size()),
136  COMPRESSION_LEVEL)
137  != Z_OK) {
138  throw std::runtime_error("Error while compressing device firmware\n");
139  }
140 
141  // Resize output buffer
142  compressBuffer.resize(compressBufferSize);
143 
144  // Set the compressed firmware
145  auto prevSize = deviceFirmware.size();
146  deviceFirmware = std::move(compressBuffer);
147 
148  auto diff = duration_cast<milliseconds>(steady_clock::now() - t1);
149  logger::debug("Compressed firmware for Dephai Application Package. Took {}, size reduced from {:.2f}MiB to {:.2f}MiB",
150  diff,
151  prevSize / (1024.0f * 1024.0f),
152  deviceFirmware.size() / (1024.0f * 1024.0f));
153  }
154 
155  // Section, MVCMD, name '__firmware'
156  sbr_section_set_name(fwSection, "__firmware");
157  sbr_section_set_bootable(fwSection, true);
158  sbr_section_set_size(fwSection, static_cast<uint32_t>(deviceFirmware.size()));
159  sbr_section_set_checksum(fwSection, sbr_compute_checksum(deviceFirmware.data(), static_cast<uint32_t>(deviceFirmware.size())));
161  if(checkChecksum) {
162  // Don't ignore checksum, use it when booting
163  sbr_section_set_ignore_checksum(fwSection, false);
164  } else {
165  // Ignore checksum to allow faster booting (images are verified after flashing, low risk)
166  sbr_section_set_ignore_checksum(fwSection, true);
167  }
168  // Set compression flags
169  if(compress) {
171  } else {
173  }
174 
175  // Section, pipeline schema, name 'pipeline'
176  sbr_section_set_name(pipelineSection, "pipeline");
177  sbr_section_set_size(pipelineSection, static_cast<uint32_t>(pipelineBinary.size()));
178  sbr_section_set_checksum(pipelineSection, sbr_compute_checksum(pipelineBinary.data(), static_cast<uint32_t>(pipelineBinary.size())));
179  sbr_section_set_offset(pipelineSection, getSectionAlignedOffset(fwSection->offset + fwSection->size));
180 
181  // Section, assets map, name 'assets'
182  sbr_section_set_name(assetsSection, "assets");
183  sbr_section_set_size(assetsSection, static_cast<uint32_t>(assetsBinary.size()));
184  sbr_section_set_checksum(assetsSection, sbr_compute_checksum(assetsBinary.data(), static_cast<uint32_t>(assetsBinary.size())));
185  sbr_section_set_offset(assetsSection, getSectionAlignedOffsetSmall(pipelineSection->offset + pipelineSection->size));
186 
187  // Section, asset storage, name 'asset_storage'
188  sbr_section_set_name(assetStorageSection, "asset_storage");
189  sbr_section_set_size(assetStorageSection, static_cast<uint32_t>(assetStorage.size()));
190  sbr_section_set_checksum(assetStorageSection, sbr_compute_checksum(assetStorage.data(), static_cast<uint32_t>(assetStorage.size())));
191  sbr_section_set_offset(assetStorageSection, getSectionAlignedOffsetSmall(assetsSection->offset + assetsSection->size));
192 
193  // Section, firmware version
194  sbr_section_set_name(fwVersionSection, "__fw_version");
195  sbr_section_set_size(fwVersionSection, static_cast<uint32_t>(fwVersionBuffer.size()));
196  sbr_section_set_checksum(fwVersionSection, sbr_compute_checksum(fwVersionBuffer.data(), static_cast<uint32_t>(fwVersionBuffer.size())));
197  sbr_section_set_offset(fwVersionSection, getSectionAlignedOffsetSmall(assetStorageSection->offset + assetStorageSection->size));
198 
199  // Section, application name
200  sbr_section_set_name(appNameSection, "app_name");
201  sbr_section_set_size(appNameSection, static_cast<uint32_t>(applicationName.size()));
202  sbr_section_set_checksum(appNameSection, sbr_compute_checksum(applicationName.data(), static_cast<uint32_t>(applicationName.size())));
203  sbr_section_set_offset(appNameSection, getSectionAlignedOffsetSmall(fwVersionSection->offset + fwVersionSection->size));
204 
205  // TODO(themarpe) - Add additional sections (Pipeline nodes will be able to use sections)
206 
207  // Create a vector to hold whole dap package
208  std::vector<uint8_t> fwPackage;
209  fwPackage.resize(lastSection->offset + lastSection->size);
210 
211  // Serialize SBR
212  sbr_serialize(&sbr, fwPackage.data(), static_cast<uint32_t>(fwPackage.size()));
213 
214  // Write to fwPackage
215  for(std::size_t i = 0; i < deviceFirmware.size(); i++) fwPackage[fwSection->offset + i] = deviceFirmware[i];
216  for(std::size_t i = 0; i < fwVersionBuffer.size(); i++) fwPackage[fwVersionSection->offset + i] = fwVersionBuffer[i];
217  for(std::size_t i = 0; i < applicationName.size(); i++) fwPackage[appNameSection->offset + i] = applicationName[i];
218  for(std::size_t i = 0; i < pipelineBinary.size(); i++) fwPackage[pipelineSection->offset + i] = pipelineBinary[i];
219  for(std::size_t i = 0; i < assetsBinary.size(); i++) fwPackage[assetsSection->offset + i] = assetsBinary[i];
220  for(std::size_t i = 0; i < assetStorage.size(); i++) fwPackage[assetStorageSection->offset + i] = assetStorage[i];
221 
222  // Debug
224  SBR_SECTION* cur = &sbr.sections[0];
225  logger::debug("DepthAI Application Package");
226  for(; cur != lastSection + 1; cur++) {
227  logger::debug("{}, {}B, {}, {}, {}, {}", cur->name, cur->size, cur->offset, cur->checksum, cur->type, cur->flags);
228  }
229  }
230 
231  return fwPackage;
232 }
233 
234 std::vector<uint8_t> DeviceBootloader::createDepthaiApplicationPackage(const Pipeline& pipeline,
235  bool compress,
236  std::string applicationName,
237  bool checkChecksum) {
238  return createDepthaiApplicationPackage(pipeline, "", compress, applicationName, checkChecksum);
239 }
240 
242  const dai::Path& path, const Pipeline& pipeline, const dai::Path& pathToCmd, bool compress, std::string applicationName, bool checkChecksum) {
243  auto dap = createDepthaiApplicationPackage(pipeline, pathToCmd, compress, applicationName, checkChecksum);
244  std::ofstream outfile(path, std::ios::binary);
245  outfile.write(reinterpret_cast<const char*>(dap.data()), dap.size());
246 }
247 
249  const dai::Path& path, const Pipeline& pipeline, bool compress, std::string applicationName, bool checkChecksum) {
250  auto dap = createDepthaiApplicationPackage(pipeline, compress, applicationName, checkChecksum);
251  std::ofstream outfile(path, std::ios::binary);
252  outfile.write(reinterpret_cast<const char*>(dap.data()), dap.size());
253 }
254 
256  init(true, {}, tl::nullopt, false);
257 }
258 
259 template <>
260 DeviceBootloader::DeviceBootloader(const DeviceInfo& devInfo, bool allowFlashingBootloader) : deviceInfo(devInfo) {
262 }
263 
264 DeviceBootloader::DeviceBootloader(const DeviceInfo& devInfo, Type type, bool allowFlashingBootloader) : deviceInfo(devInfo) {
265  init(true, {}, type, allowFlashingBootloader);
266 }
267 
268 DeviceBootloader::DeviceBootloader(const DeviceInfo& devInfo, const dai::Path& pathToBootloader, bool allowFlashingBootloader) : deviceInfo(devInfo) {
269  init(false, pathToBootloader, tl::nullopt, allowFlashingBootloader);
270 }
271 
272 DeviceBootloader::DeviceBootloader(std::string nameOrDeviceId, bool allowFlashingBootloader) : deviceInfo(std::move(nameOrDeviceId)) {
274 }
275 
277  if(monitorThread.joinable() || watchdogThread.joinable()) {
278  throw std::runtime_error("Watchdog already created. Destroy it first.");
279  }
280  watchdogRunning = true;
281  // Specify "last" ping time (5s in the future, for some grace time)
282  {
283  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
284  lastWatchdogPingTime = std::chrono::steady_clock::now() + std::chrono::seconds(5);
285  }
286  // Create monitor thread
287  monitorThread = std::thread([this]() {
288  while(watchdogRunning) {
289  // Ping with a period half of that of the watchdog timeout
290  std::this_thread::sleep_for(bootloader::XLINK_WATCHDOG_TIMEOUT);
291  // Check if wd was pinged in the specified watchdogTimeout time.
292  decltype(lastWatchdogPingTime) prevPingTime;
293  {
294  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
295  prevPingTime = lastWatchdogPingTime;
296  }
297  // Recheck if watchdogRunning wasn't already closed and close if more than twice of WD passed
298  // Bump checking thread to not cause spurious warnings/closes
299  std::chrono::milliseconds watchdogTimeout = std::chrono::milliseconds(3000);
300  if(watchdogRunning && std::chrono::steady_clock::now() - prevPingTime > watchdogTimeout * 2) {
301  logger::warn("Monitor thread (device: {} [{}]) - ping was missed, closing the device connection", deviceInfo.mxid, deviceInfo.name);
302  // ping was missed, reset the device
303  watchdogRunning = false;
304  // close the underlying connection
305  connection->close();
306  }
307  }
308  });
309 
310  // prepare watchdog thread, which will keep device alive
311  watchdogThread = std::thread([this]() {
312  try {
313  // constructor often throws in quick start/stop scenarios because
314  // the connection is close()...usually by DeviceBootloader::close()
316  std::vector<uint8_t> watchdogKeepalive = {0, 0, 0, 0};
317  std::vector<uint8_t> reset = {1, 0, 0, 0};
318  while(watchdogRunning) {
319  try {
320  stream.write(watchdogKeepalive);
321  } catch(const std::exception&) {
322  break;
323  }
324  {
325  std::unique_lock<std::mutex> lock(lastWatchdogPingTimeMtx);
326  lastWatchdogPingTime = std::chrono::steady_clock::now();
327  }
328  // Ping with a period half of that of the watchdog timeout
329  std::this_thread::sleep_for(bootloader::XLINK_WATCHDOG_TIMEOUT / 2);
330  }
331 
332  try {
333  // Send reset request
334  stream.write(reset);
335  // Dummy read (wait till link falls down)
336  const auto dummy = stream.readMove();
337  } catch(const std::exception&) {
338  // ignore
339  }
340  } catch(const std::exception&) {
341  // ignore
342  }
343 
344  // Sleep a bit, so device isn't available anymore
345  std::this_thread::sleep_for(std::chrono::milliseconds(500));
346  });
347 }
348 
350  watchdogRunning = false;
351  // Check & join previous thread
352  if(watchdogThread.joinable()) watchdogThread.join();
353  // Check & join previous thread
354  if(monitorThread.joinable()) monitorThread.join();
355 }
356 
357 void DeviceBootloader::init(bool embeddedMvcmd, const dai::Path& pathToMvcmd, tl::optional<bootloader::Type> type, bool allowBlFlash) {
358  stream = nullptr;
359  allowFlashingBootloader = allowBlFlash;
360 
361  bootloaderType = type.value_or(DEFAULT_TYPE);
362 
363  // If deviceInfo isn't fully specified (eg ANY_STATE, etc...), but id or name is - try finding it first
364  if((deviceInfo.state == X_LINK_ANY_STATE || deviceInfo.protocol == X_LINK_ANY_PROTOCOL) && (!deviceInfo.mxid.empty() || !deviceInfo.name.empty())) {
365  deviceDesc_t foundDesc;
366  auto ret = XLinkFindFirstSuitableDevice(deviceInfo.getXLinkDeviceDesc(), &foundDesc);
367  if(ret == X_LINK_SUCCESS) {
368  deviceInfo = DeviceInfo(foundDesc);
369  logger::debug("Found an actual device by given DeviceInfo: {}", deviceInfo.toString());
370  } else {
371  throw std::runtime_error("Specified device not found");
372  }
373  }
374 
375  // Below can throw - make sure to gracefully exit threads
376  try {
377  // Init device (if bootloader, handle correctly - issue USB boot command)
378  if(deviceInfo.state == X_LINK_UNBOOTED) {
379  // Unbooted device found, boot to BOOTLOADER and connect with XLinkConnection constructor
380  if(embeddedMvcmd) {
381  connection = std::make_shared<XLinkConnection>(deviceInfo, getEmbeddedBootloaderBinary(bootloaderType), X_LINK_BOOTLOADER);
382  } else {
383  connection = std::make_shared<XLinkConnection>(deviceInfo, pathToMvcmd, X_LINK_BOOTLOADER);
384  }
385 
386  // prepare bootloader stream
388 
389  // Prepare monitor & wd threads in case things go down
390  createWatchdog();
391 
392  // Retrieve bootloader version
394 
395  // Device wasn't already in bootloader, that means that embedded bootloader is booted
396  isEmbedded = true;
397  } else if(deviceInfo.state == X_LINK_BOOTLOADER || deviceInfo.state == X_LINK_FLASH_BOOTED) {
398  // If device is in flash booted state, reset to bootloader and then continue by booting appropriate FW
399  if(deviceInfo.state == X_LINK_FLASH_BOOTED) {
400  // Boot bootloader and set current deviceInfo to new device state
402  }
403 
404  // In this case boot specified bootloader only if current bootloader isn't of correct type
405  // Check version first, if >= 0.0.12 then check type and then either bootmemory to correct BL or continue as is
406 
407  // Device already in bootloader mode.
408  // Connect without booting
409  connection = std::make_shared<XLinkConnection>(deviceInfo, X_LINK_BOOTLOADER);
410 
411  // Prepare monitor & wd threads in case things go down
412  createWatchdog();
413 
414  // If type is specified, try to boot into that BL type
416 
417  // Retrieve bootloader version
420 
421  auto recommendedMinVersion = DeviceBootloader::Version(0, 0, 28);
422  if(version < recommendedMinVersion) {
423  logger::warn(
424  "[{}] [{}] Flashed bootloader version {}, less than {} is susceptible to bootup/restart failure. Upgrading is advised, flashing "
425  "main/factory (not user) bootloader. Available: {}",
428  version.toString(),
429  recommendedMinVersion.toString(),
430  getEmbeddedBootloaderVersion().toString());
431  }
432 
433  if(version >= Version(0, 0, 12)) {
434  // If version is adequate, do an in memory boot.
435 
436  // Send request for bootloader type
438  throw std::runtime_error("Error trying to connect to device");
439  }
440  // Receive response
441  Response::BootloaderType runningBootloaderType;
442  if(!receiveResponse(runningBootloaderType)) throw std::runtime_error("Error trying to connect to device");
443 
444  // Modify actual bootloader type
445  bootloaderType = runningBootloaderType.type;
446 
447  Type desiredBootloaderType = type.value_or(bootloaderType);
448 
449  // If not correct type OR if allowFlashingBootloader is set, then boot internal (latest) bootloader of correct type
450  if((desiredBootloaderType != bootloaderType) || allowFlashingBootloader) {
451  // Send request to boot firmware directly from bootloader
453  auto binary = getEmbeddedBootloaderBinary(desiredBootloaderType);
454  bootMemory.totalSize = static_cast<uint32_t>(binary.size());
455  bootMemory.numPackets = ((static_cast<uint32_t>(binary.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
456  if(!sendRequest(bootMemory)) {
457  throw std::runtime_error("Error trying to connect to device");
458  }
459 
460  // After that send numPackets of data
461  stream->writeSplit(binary.data(), binary.size(), bootloader::XLINK_STREAM_MAX_SIZE);
462  // Close existing stream first
463  stream = nullptr;
464  // Stop watchdog
465  destroyWatchdog();
466  // Close connection
467  connection->close();
468 
469  // Now reconnect
470  connection = std::make_shared<XLinkConnection>(deviceInfo, X_LINK_BOOTLOADER);
471 
472  // Recreate watchdog - monitor & wd threads in case things go down
473  createWatchdog();
474 
475  // prepare new bootloader stream
477 
478  // Retrieve bootloader version
480 
481  // The type of bootloader is now 'desiredBootloaderType'
482  bootloaderType = desiredBootloaderType;
483 
484  // Embedded bootloader was used to boot, set to true
485  isEmbedded = true;
486  } else {
487  // Just connected to existing bootloader on device. Set embedded to false
488  isEmbedded = false;
489  }
490 
491  } else {
492  // If version isn't adequate to do an in memory boot - do regular Bootloader -> USB ROM -> Boot transition.
493  Type desiredBootloaderType = type.value_or(Type::USB);
494 
495  // If not correct type OR if allowFlashingBootloader is set, then boot internal (latest) bootloader of correct type
496  if((desiredBootloaderType != Type::USB) || allowFlashingBootloader) {
497  // Send request to jump to USB bootloader
498  // Boot into USB ROM BOOTLOADER NOW
500  throw std::runtime_error("Error trying to connect to device");
501  }
502  // Close existing stream first
503  stream = nullptr;
504  // Close connection
505  connection->close();
506 
507  // Now reconnect
508  // Unbooted device found, boot to BOOTLOADER and connect with XLinkConnection constructor
509  if(embeddedMvcmd) {
510  connection = std::make_shared<XLinkConnection>(deviceInfo, getEmbeddedBootloaderBinary(desiredBootloaderType), X_LINK_BOOTLOADER);
511  } else {
512  connection = std::make_shared<XLinkConnection>(deviceInfo, pathToMvcmd, X_LINK_BOOTLOADER);
513  }
514 
515  // Prepare monitor & wd threads in case things go down
516  createWatchdog();
517 
518  // prepare bootloader stream
520 
521  // Retrieve bootloader version
523 
524  // The type of bootloader is now 'desiredBootloaderType'
525  bootloaderType = desiredBootloaderType;
526 
527  // Embedded bootloader was used to boot, set to true
528  isEmbedded = true;
529 
530  } else {
532 
533  // Just connected to existing bootloader on device. Set embedded to false
534  isEmbedded = false;
535  }
536  }
537 
538  } else {
539  throw std::runtime_error("Device not in UNBOOTED, BOOTLOADER or FLASH_BOOTED state");
540  }
541 
542  deviceInfo.state = X_LINK_BOOTLOADER;
543 
544  // Bootloader device ready, check for version
545  logger::debug("Connected bootloader version {}", version.toString());
547  logger::info("New bootloader version available. Device has: {}, available: {}", version.toString(), getEmbeddedBootloaderVersion().toString());
548  }
549 
550  } catch(...) {
551  // catchall, to properly close the threads as we are in constructor context
552  destroyWatchdog();
553  // Rethrow original exception
554  throw;
555  }
556 }
557 
559  // Only allow to close once
560  if(closed.exchange(true)) return;
561 
562  using namespace std::chrono;
563  auto t1 = steady_clock::now();
564  logger::debug("DeviceBootloader about to be closed...");
565 
566  // Close connection first; causes Xlink internal calls to unblock semaphore waits and
567  // return error codes, which then allows queues to unblock
568  // always manage ownership because other threads (e.g. watchdog) are running and need to
569  // keep the shared_ptr valid (even if closed). Otherwise leads to using null pointers,
570  // invalid memory, etc. which hard crashes main app
571  connection->close();
572 
573  // destroy Watchdog
574  destroyWatchdog();
575 
576  // Close stream
577  // BUGBUG investigate ownership; can another thread accessing this at the same time?
578  stream = nullptr;
579 
580  logger::debug("DeviceBootloader closed, {}", duration_cast<milliseconds>(steady_clock::now() - t1).count());
581 }
582 
583 // This function is thread-unsafe. The idea of "isClosed" is ephemerial and
584 // is invalid even within this function between the evaluation of the logical OR.
585 // The calculated boolean and then then return by value continue to degrade in
586 // validity to the caller
588  return closed || !watchdogRunning;
589 }
590 
592  close();
593 }
594 
596  return DeviceBootloader::Version(DEPTHAI_BOOTLOADER_VERSION);
597 }
598 
600  return version;
601 }
602 
604  return flashedVersion;
605 }
606 
608  // Send request to retrieve bootloader version
610  throw std::runtime_error("Couldn't get bootloader version");
611  }
612 
613  // Receive response
615  if(!receiveResponse(ver)) {
616  throw std::runtime_error("Couldn't parse version response");
617  }
618 
619  Version blVersion(ver.major, ver.minor, ver.patch);
620 
621  if(blVersion >= Version(Request::GetBootloaderCommit::VERSION)) {
622  // Send request to retrieve bootloader commit (skip version check)
624  stream->write((uint8_t*)&request, sizeof(request));
625 
626  // Receive response
628  if(!receiveResponse(commit)) {
629  throw std::runtime_error("Couldn't get bootloader commit");
630  }
631 
632  blVersion = Version(ver.major, ver.minor, ver.patch, commit.commitStr);
633  }
634 
635  return blVersion;
636 }
637 
639  return bootloaderType;
640 }
641 
644 }
645 
646 std::tuple<bool, std::string> DeviceBootloader::flash(
647  std::function<void(float)> progressCb, const Pipeline& pipeline, bool compress, std::string applicationName, Memory memory, bool checkCheksum) {
648  return flashDepthaiApplicationPackage(progressCb, createDepthaiApplicationPackage(pipeline, compress, applicationName, checkCheksum), memory);
649 }
650 
651 std::tuple<bool, std::string> DeviceBootloader::flash(const Pipeline& pipeline, bool compress, std::string applicationName, Memory memory, bool checkCheksum) {
652  return flashDepthaiApplicationPackage(createDepthaiApplicationPackage(pipeline, compress, applicationName, checkCheksum), memory);
653 }
654 
656  // Send request to retrieve bootloader version
658  appDetails.memory = mem;
659 
661 
662  // Receive response
664  receiveResponseThrow(details);
665 
666  // Set default values
668  info.memory = mem;
669  info.firmwareVersion = "";
670  info.applicationName = "";
671 
672  // Fill out details
673  info.hasApplication = details.hasApplication;
674  if(details.hasFirmwareVersion) {
675  info.firmwareVersion = std::string(details.firmwareVersionStr);
676  }
677  if(details.hasApplicationName) {
678  info.applicationName = std::string(details.applicationNameStr);
679  }
680 
681  if(!details.success) {
682  throw std::runtime_error(details.errorMsg);
683  }
684 
685  return info;
686 }
687 
689  if(memory == Memory::EMMC && bootloaderType == Type::USB) {
690  // Warn, as result of "no emmc" might be deceiving
691  logger::warn("USB Bootloader type does NOT support eMMC");
692  }
693 
694  // Send request to retrieve bootloader version
696  req.memory = memory;
697  sendRequestThrow(req);
698 
699  // Receive response
700  Response::MemoryDetails details;
701  receiveResponseThrow(details);
702 
703  MemoryInfo mem;
704  mem.available = details.hasMemory;
705  mem.size = details.memorySize;
706  mem.info = std::string(details.memoryInfo);
707 
708  return mem;
709 }
710 
712  // Check that type is NETWORK
713  if(getType() != Type::NETWORK) {
714  return false;
715  }
716 
717  if(!getFlashedVersion()) {
718  return false;
719  }
720 
721  // Check if bootloader version is adequate
722  if(getFlashedVersion().value().getSemver() < Version(Request::IsUserBootloader::VERSION)) {
723  return false;
724  }
725 
726  return true;
727 }
728 
730  // Check if bootloader version is adequate
731  if(getVersion().getSemver() < Version(Request::IsUserBootloader::VERSION)) {
732  return false;
733  }
734 
735  // Send request to retrieve if user bootloader is loaded
737  sendRequestThrow(req);
738 
739  // Receive response
741  receiveResponseThrow(user);
742 
743  return user.isUserBootloader;
744 }
745 
746 std::tuple<bool, std::string> DeviceBootloader::flashDepthaiApplicationPackage(std::function<void(float)> progressCb,
747  std::vector<uint8_t> package,
748  Memory memory) {
749  // Bug in NETWORK bootloader in version 0.0.12 < 0.0.14 - flashing can cause a soft brick
750  if(!getFlashedVersion()) {
751  return {false, "Can't flash DepthAI application package without knowing flashed bootloader version."};
752  }
753  auto bootloaderVersion = *getFlashedVersion();
754  if(bootloaderType == Type::NETWORK && bootloaderVersion < Version(0, 0, 14)) {
755  throw std::invalid_argument("Network bootloader requires version 0.0.14 or higher to flash applications. Current version: "
756  + bootloaderVersion.toString());
757  }
758 
759  std::tuple<bool, std::string> ret;
760  if(memory == Memory::AUTO) {
761  // send request to FLASH BOOTLOADER
762  Request::UpdateFlash updateFlash;
763  updateFlash.storage = Request::UpdateFlash::SBR;
764  updateFlash.totalSize = static_cast<uint32_t>(package.size());
765  updateFlash.numPackets = ((static_cast<uint32_t>(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
766  if(!sendRequest(updateFlash)) return {false, "Couldn't send bootloader flash request"};
767 
768  // After that send numPackets of data
769  stream->writeSplit(package.data(), package.size(), bootloader::XLINK_STREAM_MAX_SIZE);
770 
771  // Then wait for response by bootloader
772  // Wait till FLASH_COMPLETE response
774  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
775  result.errorMsg[0] = 0;
776  do {
777  std::vector<uint8_t> data;
778  if(!receiveResponseData(data)) return {false, "Couldn't receive bootloader response"};
779 
781  if(parseResponse(data, update)) {
782  // if progress callback is set
783  if(progressCb != nullptr) {
784  progressCb(update.progress);
785  }
786  } else if(parseResponse(data, result)) {
787  break;
788  } else {
789  // Unknown response, shouldn't happen
790  return {false, "Unknown response from bootloader while flashing"};
791  }
792 
793  } while(true);
794 
795  // Return if flashing was successful
796  ret = {result.success, result.errorMsg};
797 
798  } else {
799  // Flash custom
800  ret = flashCustom(memory, bootloader::getStructure(getType()).offset.at(Section::APPLICATION), package, progressCb);
801  }
802 
803  // Try specifing final app memory if set explicitly or if AUTO would be EMMC
804  try {
805  Memory finalAppMem = Memory::FLASH;
806  if(memory != Memory::AUTO) {
807  // Specify final app memory if explicitly set
808  finalAppMem = memory;
809  } else if(memory == Memory::AUTO && bootloaderType == Type::NETWORK) {
810  // If AUTO, only do so if eMMC is target memory
811  auto mem = getMemoryInfo(Memory::EMMC);
812  if(mem.available) {
813  finalAppMem = Memory::EMMC;
814  }
815  }
816 
817  // Try reading existing config, or create a new one
818  nlohmann::json configJson;
819  try {
820  configJson = readConfigData();
821  } catch(const std::exception& ex) {
822  logger::debug("Error while trying to read existing bootloader configuration: {}", ex.what());
823  }
824  // Set the following field 'appMem' (in forward/backward compat manner)
825  configJson["appMem"] = finalAppMem;
826  // Flash back the rest of configuration as is
827  bool success;
828  std::string errorMsg;
829  std::tie(success, errorMsg) = flashConfigData(configJson);
830  if(success) {
831  logger::debug("Success flashing the appMem configuration to '{}'", static_cast<std::int32_t>(finalAppMem));
832  } else {
833  throw std::runtime_error(errorMsg);
834  }
835  } catch(const std::exception& ex) {
836  logger::debug("Error while trying to specify final appMem configuration: {}", ex.what());
837  }
838 
839  return ret;
840 }
841 
842 std::tuple<bool, std::string> DeviceBootloader::flashDepthaiApplicationPackage(std::vector<uint8_t> package, Memory memory) {
843  return flashDepthaiApplicationPackage(nullptr, package, memory);
844 }
845 
846 std::tuple<bool, std::string> DeviceBootloader::flashClear(Memory memory) {
847  std::vector<uint8_t> clear;
848  for(size_t i = 0; i < SBR_RAW_SIZE; i++) {
849  clear.push_back(0xFF);
850  }
851  return flashCustom(memory, bootloader::getStructure(getType()).offset.at(Section::APPLICATION), clear);
852 }
853 
854 std::tuple<bool, std::string> DeviceBootloader::flashBootloader(std::function<void(float)> progressCb, const dai::Path& path) {
855  return flashBootloader(Memory::FLASH, bootloaderType, progressCb, path);
856 }
857 
858 std::tuple<bool, std::string> DeviceBootloader::flashBootloader(Memory memory, Type type, std::function<void(float)> progressCb, const dai::Path& path) {
859  // Check if 'allowFlashingBootloader' is set to true.
861  throw std::invalid_argument("DeviceBootloader wasn't initialized to allow flashing bootloader. Set 'allowFlashingBootloader' in constructor");
862  }
863 
864  // Set specific type if AUTO
865  if(type == Type::AUTO) {
866  type = getType();
867  }
868 
869  // Only flash memory is supported for now
870  if(memory != Memory::FLASH) {
871  throw std::invalid_argument("Only FLASH memory is supported for now");
872  }
873  if(bootloaderType != type && getVersion() < Version(Request::UpdateFlashEx2::VERSION)) {
874  throw std::runtime_error("Current bootloader version doesn't support flashing different type of bootloader");
875  }
876 
877  std::vector<uint8_t> package;
878  if(!path.empty()) {
879  std::ifstream fwStream(path, std::ios::binary);
880  if(!fwStream.is_open()) throw std::runtime_error(fmt::format("Cannot flash bootloader, binary at path: {} doesn't exist", path));
881  package = std::vector<std::uint8_t>(std::istreambuf_iterator<char>(fwStream), {});
882  } else {
883  package = getEmbeddedBootloaderBinary(type);
884  }
885 
886  // If booted and desired bootloader types don't match
887  // Use UpdateFlashEx2 instead to properly flash
888  if(bootloaderType == type) {
889  // Old command
890 
891  // send request to FLASH BOOTLOADER
892  Request::UpdateFlash updateFlash;
893  updateFlash.storage = Request::UpdateFlash::BOOTLOADER;
894  updateFlash.totalSize = static_cast<uint32_t>(package.size());
895  updateFlash.numPackets = ((static_cast<uint32_t>(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
896  if(!sendRequest(updateFlash)) return {false, "Couldn't send bootloader flash request"};
897 
898  } else {
899  // send request to FLASH BOOTLOADER
900  Request::UpdateFlashEx2 updateFlashEx2;
901  updateFlashEx2.memory = memory;
903  updateFlashEx2.totalSize = static_cast<uint32_t>(package.size());
904  updateFlashEx2.numPackets = ((static_cast<uint32_t>(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
905  if(!sendRequest(updateFlashEx2)) return {false, "Couldn't send bootloader flash request"};
906  }
907 
908  // After that send numPackets of data
909  stream->writeSplit(package.data(), package.size(), bootloader::XLINK_STREAM_MAX_SIZE);
910 
911  // Then wait for response by bootloader
912  // Wait till FLASH_COMPLETE response
914  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
915  result.errorMsg[0] = 0;
916  do {
917  std::vector<uint8_t> data;
918  if(!receiveResponseData(data)) return {false, "Couldn't receive bootloader response"};
919 
921  if(parseResponse(data, update)) {
922  // if progress callback is set
923  if(progressCb != nullptr) {
924  progressCb(update.progress);
925  }
926  // if flash complete response arrived, break from while loop
927  } else if(parseResponse(data, result)) {
928  break;
929  } else {
930  // Unknown response, shouldn't happen
931  return {false, "Unknown response from bootloader while flashing"};
932  }
933 
934  } while(true);
935 
936  // Return if flashing was successful
937  return {result.success, result.errorMsg};
938 }
939 
940 std::tuple<bool, std::string> DeviceBootloader::flashUserBootloader(std::function<void(float)> progressCb, const dai::Path& path) {
941  // Check that type is NETWORK
942  const auto type = Type::NETWORK;
943  if(getType() != Type::NETWORK) {
944  throw std::runtime_error("Flashing User Bootloader is only available for NETWORK bootloaders");
945  }
946  // Only flash memory is supported for now
947  const auto memory = Memory::FLASH;
948  // if(memory != Memory::FLASH) {
949  // throw std::invalid_argument("Only FLASH memory is supported for now");
950  // }
951 
952  // Check if bootloader version is adequate
953  if(!getFlashedVersion()) {
954  throw std::runtime_error(
955  "Couldn't retrieve version of the flashed bootloader. Make sure you have a factory bootloader flashed and the device is booted to bootloader.");
956  }
957  if(getFlashedVersion().value().getSemver() < Version(Request::IsUserBootloader::VERSION)) {
958  throw std::runtime_error(fmt::format("Current bootloader version doesn't support User Bootloader. Current version: {}, minimum required version: {}",
959  getFlashedVersion().value().toStringSemver(),
960  Version(Request::IsUserBootloader::VERSION).toStringSemver()));
961  }
962 
963  // Retrieve bootloader
964  std::vector<uint8_t> package;
965  if(!path.empty()) {
966  std::ifstream fwStream(path, std::ios::binary);
967  if(!fwStream.is_open()) throw std::runtime_error(fmt::format("Cannot flash User Bootloader, binary at path: {} doesn't exist", path));
968  package = std::vector<std::uint8_t>(std::istreambuf_iterator<char>(fwStream), {});
969  } else {
970  package = getEmbeddedBootloaderBinary(type);
971  }
972 
973  // Send request to FLASH USER BOOTLOADER
974  Request::UpdateFlashEx2 updateFlashEx2;
975  updateFlashEx2.memory = memory;
976  updateFlashEx2.offset = dai::bootloader::getStructure(type).offset.at(Section::USER_BOOTLOADER);
977  updateFlashEx2.totalSize = static_cast<uint32_t>(package.size());
978  updateFlashEx2.numPackets = ((static_cast<uint32_t>(package.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
979 
980  // Checks first
981  const auto MAX_USER_BOOTLOADER_SIZE = dai::bootloader::getStructure(type).size.at(Section::USER_BOOTLOADER);
982  if(static_cast<long>(updateFlashEx2.totalSize) > MAX_USER_BOOTLOADER_SIZE) {
983  throw std::runtime_error(fmt::format("Selected User Bootloader is too large {} / {}B", updateFlashEx2.totalSize, MAX_USER_BOOTLOADER_SIZE));
984  }
985 
986  if(!sendRequest(updateFlashEx2)) return {false, "Couldn't send bootloader flash request"};
987 
988  // After that send numPackets of data
989  stream->writeSplit(package.data(), package.size(), bootloader::XLINK_STREAM_MAX_SIZE);
990 
991  // Then wait for response by bootloader
992  // Wait till FLASH_COMPLETE response
994  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
995  result.errorMsg[0] = 0;
996  do {
997  std::vector<uint8_t> data;
998  if(!receiveResponseData(data)) return {false, "Couldn't receive bootloader response"};
999 
1001  if(parseResponse(data, update)) {
1002  // if progress callback is set
1003  if(progressCb != nullptr) {
1004  progressCb(update.progress);
1005  }
1006  // if flash complete response arrived, break from while loop
1007  } else if(parseResponse(data, result)) {
1008  break;
1009  } else {
1010  // Unknown response, shouldn't happen
1011  return {false, "Unknown response from bootloader while flashing"};
1012  }
1013 
1014  } while(true);
1015 
1016  // Calculate checksum and update config
1017  // Try reading existing config, or create a new one
1018  nlohmann::json configJson;
1019  try {
1020  configJson = readConfigData();
1021  } catch(const std::exception& ex) {
1022  logger::debug("Error while trying to read existing bootloader configuration: {}", ex.what());
1023  }
1024  // Set the userBl fields (in forward/backward compat manner)
1025  const auto userBlSize = static_cast<std::uint32_t>(package.size());
1026  const auto userBlChecksum = sbr_compute_checksum(package.data(), static_cast<uint32_t>(package.size()));
1027  configJson["userBlSize"] = userBlSize;
1028  configJson["userBlChecksum"] = userBlChecksum;
1029  // Flash back the rest of configuration as is
1030  bool success;
1031  std::string errorMsg;
1032  std::tie(success, errorMsg) = flashConfigData(configJson);
1033  if(success) {
1034  logger::debug("Success flashing the configuration userBlSize to '{}' and userBlChecksum to '{}'", userBlSize, userBlChecksum);
1035  } else {
1036  throw std::runtime_error(errorMsg);
1037  }
1038 
1039  // Return if flashing was successful
1040  return {result.success, result.errorMsg};
1041 }
1042 
1043 std::tuple<bool, std::string> DeviceBootloader::flashGpioModeBootHeader(Memory memory, int gpioMode) {
1044  // TODO(themarpe) - use memory param
1045  (void)memory;
1046 
1047  Request::UpdateFlashBootHeader updateBootHeader;
1048  updateBootHeader.type = Request::UpdateFlashBootHeader::GPIO_MODE;
1049  updateBootHeader.gpioMode = gpioMode;
1050 
1051  // Send & Get response
1052  if(!sendRequest(updateBootHeader)) return {false, "Couldn't send request to flash boot header"};
1053  Response::FlashComplete resp = {};
1054  receiveResponse(resp);
1055  return {resp.success, resp.errorMsg};
1056 }
1057 
1058 std::tuple<bool, std::string> DeviceBootloader::flashUsbRecoveryBootHeader(Memory memory) {
1059  // TODO(themarpe) - use memory param
1060  (void)memory;
1061 
1062  Request::UpdateFlashBootHeader updateBootHeader;
1063  updateBootHeader.type = Request::UpdateFlashBootHeader::USB_RECOVERY;
1064 
1065  // Send & Get response
1066  if(!sendRequest(updateBootHeader)) return {false, "Couldn't send request to flash boot header"};
1067  Response::FlashComplete resp = {};
1068  receiveResponse(resp);
1069  return {resp.success, resp.errorMsg};
1070 }
1071 
1072 std::tuple<bool, std::string> DeviceBootloader::flashBootHeader(Memory memory, int32_t frequency, int64_t location, int32_t dummyCycles, int64_t offset) {
1073  // TODO(themarpe) - use memory param
1074  (void)memory;
1075 
1076  Request::UpdateFlashBootHeader updateBootHeader;
1077  updateBootHeader.type = Request::UpdateFlashBootHeader::NORMAL;
1078  updateBootHeader.offset = offset;
1079  updateBootHeader.location = location;
1080  updateBootHeader.dummyCycles = dummyCycles;
1081  updateBootHeader.frequency = frequency;
1082  // Set optimized gpio boot mode, which allows changing above parameters
1083  updateBootHeader.gpioMode = 0x7;
1084 
1085  // Send & Get response
1086  if(!sendRequest(updateBootHeader)) return {false, "Couldn't send request to flash boot header"};
1087  Response::FlashComplete resp = {};
1088  receiveResponse(resp);
1089  return {resp.success, resp.errorMsg};
1090 }
1091 
1092 std::tuple<bool, std::string> DeviceBootloader::flashFastBootHeader(Memory memory, int32_t frequency, int64_t location, int32_t dummyCycles, int64_t offset) {
1093  // TODO(themarpe) - use memory param
1094  (void)memory;
1095 
1096  Request::UpdateFlashBootHeader updateBootHeader;
1097  updateBootHeader.type = Request::UpdateFlashBootHeader::FAST;
1098  updateBootHeader.offset = offset;
1099  updateBootHeader.location = location;
1100  updateBootHeader.dummyCycles = dummyCycles;
1101  updateBootHeader.frequency = frequency;
1102  // Set optimized gpio boot mode, which allows changing above parameters
1103  updateBootHeader.gpioMode = 0x7;
1104 
1105  // Send & Get response
1106  if(!sendRequest(updateBootHeader)) return {false, "Couldn't send request to flash boot header"};
1107  Response::FlashComplete resp = {};
1108  receiveResponse(resp);
1109  return {resp.success, resp.errorMsg};
1110 }
1111 
1112 std::tuple<bool, std::string> DeviceBootloader::flashCustom(Memory memory,
1113  size_t offset,
1114  const std::vector<uint8_t>& data,
1115  std::function<void(float)> progressCb) {
1116  if(data.size() == 0) {
1117  throw std::invalid_argument("Size to flash is zero");
1118  }
1119  return flashCustom(memory, offset, data.data(), data.size(), "", progressCb);
1120 }
1121 std::tuple<bool, std::string> DeviceBootloader::flashCustom(
1122  Memory memory, size_t offset, const uint8_t* data, size_t size, std::function<void(float)> progressCb) {
1123  if(data == nullptr || size == 0) {
1124  throw std::invalid_argument("Data is nullptr or size is zero");
1125  }
1126  return flashCustom(memory, offset, data, size, "", progressCb);
1127 }
1128 std::tuple<bool, std::string> DeviceBootloader::flashCustom(Memory memory, size_t offset, std::string filename, std::function<void(float)> progressCb) {
1129  return flashCustom(memory, offset, nullptr, 0, filename, progressCb);
1130 }
1131 std::tuple<bool, std::string> DeviceBootloader::flashCustom(
1132  Memory memory, size_t offset, const uint8_t* data, size_t size, std::string filename, std::function<void(float)> progressCb) {
1133  // // Only flash memory is supported for now
1134  // if(memory != Memory::FLASH) {
1135  // throw std::invalid_argument("Only FLASH memory is supported for now");
1136  // }
1137  if(getVersion() < Version(0, 0, 12)) {
1138  throw std::runtime_error("Current bootloader version doesn't support custom flashing");
1139  }
1140 
1141  std::vector<uint8_t> optFileData;
1142  if(!filename.empty()) {
1143  // Read file into memory first
1144  std::ifstream optFile(filename, std::ios::in | std::ios::binary);
1145  optFileData = std::vector<std::uint8_t>(std::istreambuf_iterator<char>(optFile), {});
1146  data = optFileData.data();
1147  size = optFileData.size();
1148  }
1149 
1150  // send request to FLASH BOOTLOADER
1151  Request::UpdateFlashEx2 updateFlashEx2;
1152  updateFlashEx2.memory = memory;
1153  updateFlashEx2.offset = static_cast<uint32_t>(offset);
1154  updateFlashEx2.totalSize = static_cast<uint32_t>(size);
1155  updateFlashEx2.numPackets = ((static_cast<uint32_t>(size) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
1156  if(!sendRequest(updateFlashEx2)) return {false, "Couldn't send bootloader flash request"};
1157 
1158  // After that send numPackets of data
1160 
1161  // Then wait for response by bootloader
1162  // Wait till FLASH_COMPLETE response
1163  Response::FlashComplete result;
1164  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
1165  result.errorMsg[0] = 0;
1166  do {
1167  std::vector<uint8_t> responseData;
1168  if(!receiveResponseData(responseData)) return {false, "Couldn't receive bootloader response"};
1169 
1171  if(parseResponse(responseData, update)) {
1172  // if progress callback is set
1173  if(progressCb != nullptr) {
1174  progressCb(update.progress);
1175  }
1176  // if flash complete response arrived, break from while loop
1177  } else if(parseResponse(responseData, result)) {
1178  break;
1179  } else {
1180  // Unknown response, shouldn't happen
1181  return {false, "Unknown response from bootloader while flashing"};
1182  }
1183 
1184  } while(true);
1185 
1186  // Return if flashing was successful
1187  return {result.success, result.errorMsg};
1188 }
1189 
1190 std::tuple<bool, std::string> DeviceBootloader::readCustom(
1191  Memory memory, size_t offset, size_t size, std::vector<uint8_t>& data, std::function<void(float)> progressCb) {
1192  // Resize container if not too small
1193  if(data.size() < size) {
1194  data.resize(size);
1195  }
1196  return readCustom(memory, offset, size, data.data(), "", progressCb);
1197 }
1198 std::tuple<bool, std::string> DeviceBootloader::readCustom(Memory memory, size_t offset, size_t size, uint8_t* data, std::function<void(float)> progressCb) {
1199  return readCustom(memory, offset, size, data, "", progressCb);
1200 }
1201 std::tuple<bool, std::string> DeviceBootloader::readCustom(
1202  Memory memory, size_t offset, size_t size, std::string filename, std::function<void(float)> progressCb) {
1203  return readCustom(memory, offset, size, nullptr, filename, progressCb);
1204 }
1205 std::tuple<bool, std::string, std::vector<uint8_t>> DeviceBootloader::readCustom(Memory memory,
1206  size_t offset,
1207  size_t size,
1208  std::function<void(float)> progressCb) {
1209  std::vector<uint8_t> data;
1210  auto ret = readCustom(memory, offset, size, data, progressCb);
1211  return {std::get<0>(ret), std::get<1>(ret), data};
1212 }
1213 
1214 std::tuple<bool, std::string> DeviceBootloader::readCustom(
1215  Memory memory, size_t offset, size_t size, uint8_t* data, std::string filename, std::function<void(float)> progressCb) {
1216  // // Only flash memory is supported for now
1217  // if(memory != Memory::FLASH) {
1218  // throw std::invalid_argument("Only FLASH memory is supported for now");
1219  // }
1220 
1221  // send request to Read Flash
1222  Request::ReadFlash readFlash;
1223  readFlash.memory = memory;
1224  readFlash.offset = static_cast<uint32_t>(offset);
1225  readFlash.totalSize = static_cast<uint32_t>(size);
1226  if(!sendRequest(readFlash)) return {false, "Couldn't send bootloader flash request"};
1227 
1228  // Then wait for response by bootloader
1229  Response::ReadFlash response;
1230  receiveResponse(response);
1231  // If error
1232  if(!response.success) {
1233  return {false, std::string(response.errorMsg)};
1234  }
1235 
1236  // Read numPackets of data
1237  if(filename.empty()) {
1238  // Read to buffer
1239  size_t dataOffset = 0;
1240  for(unsigned i = 0; i < response.numPackets; i++) {
1241  auto d = stream->read();
1242  memcpy(data + dataOffset, d.data(), d.size());
1243  dataOffset += d.size();
1244  if(progressCb) progressCb((1.0f / response.numPackets) * (i + 1));
1245  }
1246  } else {
1247  // Write to file
1248  std::ofstream outputFile(filename);
1249  for(unsigned i = 0; i < response.numPackets; i++) {
1250  auto d = stream->read();
1251  outputFile.write(reinterpret_cast<char*>(d.data()), d.size());
1252  if(progressCb) progressCb((1.0f / response.numPackets) * (i + 1));
1253  }
1254  }
1255 
1256  // Return if flashing was successful
1257  return {response.success, response.errorMsg};
1258 }
1259 
1261  // Send request to GET_BOOTLOADER_CONFIG
1262  Request::GetBootloaderConfig getConfigReq;
1263  getConfigReq.memory = memory;
1264 
1265  if(type != Type::AUTO) {
1266  const auto confStructure = bootloader::getStructure(type);
1267  getConfigReq.offset = confStructure.offset.at(bootloader::Section::BOOTLOADER_CONFIG);
1268  getConfigReq.maxSize = confStructure.size.at(bootloader::Section::BOOTLOADER_CONFIG);
1269  } else {
1270  // leaves as default values, which correspond to AUTO
1271  }
1272 
1273  sendRequestThrow(getConfigReq);
1274 
1275  // Get response
1277  resp.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
1278 
1279  receiveResponseThrow(resp);
1280  if(resp.success) {
1281  // Read back bootloader config (1 packet max)
1282  auto bsonConfig = stream->read();
1283  // Parse from BSON
1284  return nlohmann::json::from_bson(bsonConfig);
1285  } else {
1286  throw std::runtime_error(resp.errorMsg);
1287  }
1288 }
1289 
1290 std::tuple<bool, std::string> DeviceBootloader::flashConfigClear(Memory memory, Type type) {
1291  // send request to SET_BOOTLOADER_CONFIG
1292  Request::SetBootloaderConfig setConfigReq;
1293  setConfigReq.memory = memory;
1294  if(type != Type::AUTO) {
1296  }
1297 
1298  setConfigReq.numPackets = 0;
1299  setConfigReq.totalSize = 0;
1300  setConfigReq.clearConfig = 1;
1301  if(!sendRequest(setConfigReq)) return {false, "Couldn't send request to flash configuration clear"};
1302 
1303  // Read back response
1304  Response::FlashComplete result;
1305  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
1306  result.errorMsg[0] = 0;
1307  if(!receiveResponse(result)) {
1308  return {false, "Couldn't receive response to flash configuration clear"};
1309  }
1310 
1311  // Return if flashing was successful
1312  return {result.success, result.errorMsg};
1313 }
1314 
1315 std::tuple<bool, std::string> DeviceBootloader::flashConfigData(nlohmann::json configData, Memory memory, Type type) {
1316  // Parse to BSON
1317  auto bson = nlohmann::json::to_bson(configData);
1318 
1319  // Send request to SET_BOOTLOADER_CONFIG
1320  Request::SetBootloaderConfig setConfigReq;
1321  setConfigReq.memory = memory;
1322  if(type != Type::AUTO) {
1324  }
1325  setConfigReq.numPackets = 1;
1326  setConfigReq.totalSize = static_cast<decltype(setConfigReq.totalSize)>(bson.size());
1327  setConfigReq.clearConfig = 0;
1328  if(!sendRequest(setConfigReq)) return {false, "Couldn't send request to flash configuration data"};
1329 
1330  // Send 1 packet, of bson config data
1331  stream->write(bson);
1332 
1333  // Read back response
1334  Response::FlashComplete result;
1335  result.success = 0; // TODO remove these inits after fix https://github.com/luxonis/depthai-bootloader-shared/issues/4
1336  result.errorMsg[0] = 0;
1337  if(!receiveResponse(result)) {
1338  return {false, "Couldn't receive response to flash configuration data"};
1339  }
1340 
1341  // Return if flashing was successful
1342  return {result.success, result.errorMsg};
1343 }
1344 
1345 std::tuple<bool, std::string> DeviceBootloader::flashConfigFile(const dai::Path& configPath, Memory memory, Type type) {
1346  // read a JSON file
1347  std::ifstream configInputStream(configPath);
1348  if(!configInputStream.is_open()) throw std::runtime_error(fmt::format("Cannot flash configuration, JSON at path: {} doesn't exist", configPath));
1349  nlohmann::json configJson;
1350  configInputStream >> configJson;
1351  return flashConfigData(configJson, memory, type);
1352 }
1353 
1355  auto json = readConfigData(memory, type);
1356  return Config::fromJson(json);
1357 }
1358 
1359 std::tuple<bool, std::string> DeviceBootloader::flashConfig(const Config& config, Memory memory, Type type) {
1360  return flashConfigData(config.toJson(), memory, type);
1361 }
1362 
1363 // Boot memory
1364 void DeviceBootloader::bootMemory(const std::vector<uint8_t>& embeddedFw) {
1365  // Send request to boot firmware directly from bootloader
1367  bootMemory.totalSize = static_cast<uint32_t>(embeddedFw.size());
1368  bootMemory.numPackets = ((static_cast<uint32_t>(embeddedFw.size()) - 1) / bootloader::XLINK_STREAM_MAX_SIZE) + 1;
1369  if(!sendRequest(bootMemory)) {
1370  throw std::runtime_error("Error trying to connect to device");
1371  }
1372 
1373  // After that send numPackets of data
1374  stream->writeSplit(embeddedFw.data(), embeddedFw.size(), bootloader::XLINK_STREAM_MAX_SIZE);
1375 
1376  // Then wait for the link to fall down
1377  try {
1378  stream->read();
1379  } catch(const std::exception&) {
1380  // ignore
1381  }
1382 }
1383 
1385  // Boot into USB ROM BOOTLOADER now
1387  throw std::runtime_error("Error trying to connect to device");
1388  }
1389 
1390  // Then wait for the link to fall down
1391  try {
1392  stream->read();
1393  } catch(const std::exception&) {
1394  // ignore
1395  }
1396 }
1397 
1399  return isEmbedded;
1400 }
1401 
1404 }
1405 
1406 template <typename T>
1407 bool DeviceBootloader::sendRequest(const T& request) {
1408  if(stream == nullptr) return false;
1409 
1410  // Do a version check beforehand (compare just the semver)
1411  if(getVersion().getSemver() < Version(T::VERSION)) {
1412  throw std::runtime_error(
1413  fmt::format("Bootloader version {} required to send request '{}'. Current version {}", T::VERSION, T::NAME, getVersion().toString()));
1414  }
1415 
1416  try {
1417  stream->write((uint8_t*)&request, sizeof(T));
1418  } catch(const std::exception&) {
1419  return false;
1420  }
1421 
1422  return true;
1423 }
1424 
1425 template <typename T>
1426 void DeviceBootloader::sendRequestThrow(const T& request) {
1427  if(stream == nullptr) throw std::runtime_error("Couldn't send request. Stream is null");
1428 
1429  // Do a version check beforehand (compare just the semver)
1430  if(getVersion().getSemver() < Version(T::VERSION)) {
1431  throw std::runtime_error(
1432  fmt::format("Bootloader version {} required to send request '{}'. Current version {}", T::VERSION, T::NAME, getVersion().toString()));
1433  }
1434 
1435  try {
1436  stream->write((uint8_t*)&request, sizeof(T));
1437  } catch(const std::exception&) {
1438  throw std::runtime_error("Couldn't send " + std::string(T::NAME) + " request");
1439  }
1440 }
1441 
1442 bool DeviceBootloader::receiveResponseData(std::vector<uint8_t>& data) {
1443  if(stream == nullptr) return false;
1444 
1445  data = stream->read();
1446  return true;
1447 }
1448 
1449 template <typename T>
1450 bool DeviceBootloader::parseResponse(const std::vector<uint8_t>& data, T& response) {
1451  // Checks that 'data' is type T
1452  Response::Command command;
1453  if(data.size() < sizeof(command)) return false;
1454  memcpy(&command, data.data(), sizeof(command));
1455  if(response.cmd != command) return false;
1456  if(data.size() < sizeof(response)) return false;
1457 
1458  // If yes, memcpy to response
1459  memcpy(&response, data.data(), sizeof(response));
1460  return true;
1461 }
1462 
1463 template <typename T>
1465  if(stream == nullptr) return false;
1466  // Receive data first
1467  std::vector<uint8_t> data;
1468  if(!receiveResponseData(data)) return false;
1469 
1470  // Then try to parse
1471  if(!parseResponse(data, response)) return false;
1472 
1473  return true;
1474 }
1475 
1476 template <typename T>
1478  if(stream == nullptr) throw std::runtime_error("Couldn't receive response. Stream is null");
1479 
1480  // Receive data first
1481  std::vector<uint8_t> data;
1482  if(!receiveResponseData(data)) {
1483  throw std::runtime_error("Couldn't receive " + std::string(T::NAME) + " response");
1484  }
1485 
1486  // Then try to parse
1487  if(!parseResponse(data, response)) {
1488  throw std::runtime_error("Couldn't parse " + std::string(T::NAME) + " response");
1489  }
1490 }
1491 
1492 // Config functions
1493 void DeviceBootloader::Config::setStaticIPv4(std::string ip, std::string mask, std::string gateway) {
1494  network.ipv4 = platform::getIPv4AddressAsBinary(ip);
1495  network.ipv4Mask = platform::getIPv4AddressAsBinary(mask);
1496  network.ipv4Gateway = platform::getIPv4AddressAsBinary(gateway);
1497  network.staticIpv4 = true;
1498 }
1499 void DeviceBootloader::Config::setDynamicIPv4(std::string ip, std::string mask, std::string gateway) {
1500  network.ipv4 = platform::getIPv4AddressAsBinary(ip);
1501  network.ipv4Mask = platform::getIPv4AddressAsBinary(mask);
1502  network.ipv4Gateway = platform::getIPv4AddressAsBinary(gateway);
1503  network.staticIpv4 = false;
1504 }
1505 
1507  return network.staticIpv4;
1508 }
1509 
1511  return platform::getIPv4AddressAsString(network.ipv4);
1512 }
1514  return platform::getIPv4AddressAsString(network.ipv4Mask);
1515 }
1517  return platform::getIPv4AddressAsString(network.ipv4Gateway);
1518 }
1519 
1520 void DeviceBootloader::Config::setDnsIPv4(std::string dns, std::string dnsAlt) {
1521  network.ipv4Dns = platform::getIPv4AddressAsBinary(dns);
1522  network.ipv4DnsAlt = platform::getIPv4AddressAsBinary(dnsAlt);
1523 }
1524 
1526  return platform::getIPv4AddressAsString(network.ipv4Dns);
1527 }
1528 
1530  return platform::getIPv4AddressAsString(network.ipv4DnsAlt);
1531 }
1532 
1533 void DeviceBootloader::Config::setUsbTimeout(std::chrono::milliseconds ms) {
1534  usb.timeoutMs = static_cast<decltype(usb.timeoutMs)>(ms.count());
1535 }
1536 
1537 std::chrono::milliseconds DeviceBootloader::Config::getUsbTimeout() {
1538  return std::chrono::milliseconds(usb.timeoutMs);
1539 }
1540 
1541 void DeviceBootloader::Config::setNetworkTimeout(std::chrono::milliseconds ms) {
1542  network.timeoutMs = static_cast<decltype(network.timeoutMs)>(ms.count());
1543 }
1544 
1545 std::chrono::milliseconds DeviceBootloader::Config::getNetworkTimeout() {
1546  return std::chrono::milliseconds(network.timeoutMs);
1547 }
1548 
1550  usb.maxUsbSpeed = static_cast<int>(speed);
1551 }
1552 
1554  return static_cast<UsbSpeed>(usb.maxUsbSpeed);
1555 }
1556 
1558  std::array<uint8_t, 6> a = {0, 0, 0, 0, 0, 0};
1559  if(mac != "") {
1560  int last = -1;
1561  int rc = std::sscanf(mac.c_str(), "%hhx:%hhx:%hhx:%hhx:%hhx:%hhx%n", &a[0], &a[1], &a[2], &a[3], &a[4], &a[5], &last);
1562  if(rc != 6 || static_cast<long>(mac.size()) != last) {
1563  throw std::invalid_argument("Invalid MAC address format " + mac);
1564  }
1565  }
1566 
1567  // Set the parsed mac address
1568  network.mac = a;
1569 }
1571  // 32 characters is adequite for MAC address representation
1572  std::array<char, 32> macStr = {};
1573  std::snprintf(macStr.data(),
1574  macStr.size(),
1575  "%02X:%02X:%02X:%02X:%02X:%02X",
1576  network.mac[0],
1577  network.mac[1],
1578  network.mac[2],
1579  network.mac[3],
1580  network.mac[4],
1581  network.mac[5]);
1582 
1583  return std::string(macStr.data());
1584 }
1585 
1586 nlohmann::json DeviceBootloader::Config::toJson() const {
1587  // Get current config & add data (but don't override)
1588  nlohmann::json configValues = *this;
1589  auto dataCopy = data;
1590  dataCopy.update(configValues);
1591  return dataCopy;
1592 }
1593 
1595  // Parse out json (implicitly) and
1596  Config cfg = json;
1597  // save json data as is (to retain unknown values)
1598  cfg.data = json;
1599  return cfg;
1600 }
1601 
1602 } // namespace dai
dai::bootloader::response::GetBootloaderConfig::success
uint32_t success
Definition: Bootloader.hpp:334
SBR_SECTION::flags
uint8_t flags
Definition: SBR.h:34
dai::bootloader::request::SetBootloaderConfig::clearConfig
uint32_t clearConfig
Definition: Bootloader.hpp:151
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::bootloader::XLINK_STREAM_MAX_SIZE
constexpr static std::uint32_t XLINK_STREAM_MAX_SIZE
Definition: depthai-bootloader-shared/include/depthai-bootloader-shared/XLinkConstants.hpp:15
dai::bootloader::response::MemoryDetails::hasMemory
uint32_t hasMemory
Definition: Bootloader.hpp:418
SBR_SECTION
Definition: SBR.h:28
sbr_compute_checksum
uint32_t sbr_compute_checksum(const void *buffer, uint32_t size)
Definition: SBR.c:168
dai::bootloader::request::GetMemoryDetails::memory
Memory memory
Definition: Bootloader.hpp:242
dai::DeviceBootloader::readConfig
Config readConfig(Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1354
dai::Path::empty
bool empty() const noexcept
Observes if path is empty (contains no string/folders/filename)
Definition: Path.hpp:194
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
dai::DeviceBootloader::MemoryInfo
Definition: DeviceBootloader.hpp:99
Pipeline.hpp
dai::bootloader::request::UpdateFlashBootHeader::location
int64_t location
Definition: Bootloader.hpp:203
dai::DeviceBootloader::Config::getDnsAltIPv4
std::string getDnsAltIPv4()
Get alternate IPv4 DNS server.
Definition: DeviceBootloader.cpp:1529
dai::DeviceBootloader::close
void close()
Definition: DeviceBootloader.cpp:558
dai::UsbSpeed
UsbSpeed
Definition: shared/depthai-shared/include/depthai-shared/common/UsbSpeed.hpp:12
dai::bootloader::Section::BOOTLOADER
@ BOOTLOADER
dai::bootloader::Memory::AUTO
@ AUTO
dai::DeviceBootloader::Config::toJson
nlohmann::json toJson() const
To JSON.
Definition: DeviceBootloader.cpp:1586
dai::bootloader::response::MemoryDetails::memoryInfo
char memoryInfo[512]
Definition: Bootloader.hpp:421
dai::bootloader::request::UpdateFlashEx2::offset
uint32_t offset
Definition: Bootloader.hpp:123
dai::DeviceBootloader::bootUsbRomBootloader
void bootUsbRomBootloader()
Definition: DeviceBootloader.cpp:1384
dai::bootloader::request::ReadFlash::memory
Memory memory
Definition: Bootloader.hpp:218
dai::DeviceInfo
Definition: XLinkConnection.hpp:27
dai::bootloader::request::UpdateFlashEx2::numPackets
uint32_t numPackets
Definition: Bootloader.hpp:125
dai::DeviceBootloader::Config::fromJson
static Config fromJson(nlohmann::json)
from JSON
Definition: DeviceBootloader.cpp:1594
dai::DeviceBootloader::flashGpioModeBootHeader
std::tuple< bool, std::string > flashGpioModeBootHeader(Memory memory, int gpioMode)
Definition: DeviceBootloader.cpp:1043
dai::bootloader::response::ReadFlash
Definition: Bootloader.hpp:379
sbr_section_set_size
void sbr_section_set_size(SBR_SECTION *sbr_section, uint32_t size)
Definition: SBR.c:177
dai::bootloader::request::ReadFlash::totalSize
uint32_t totalSize
Definition: Bootloader.hpp:220
dai::XLinkConnection::bootBootloader
static DeviceInfo bootBootloader(const DeviceInfo &devInfo)
Definition: XLinkConnection.cpp:221
dai::bootloader::request::GetBootloaderConfig
Definition: Bootloader.hpp:159
dai::DeviceInfo::toString
std::string toString() const
Definition: XLinkConnection.cpp:79
dai::bootloader::response::BootloaderCommit::commitStr
char commitStr[64]
Definition: Bootloader.hpp:372
sbr_section_set_compression
void sbr_section_set_compression(SBR_SECTION *sbr_section, SBR_COMPRESSION compression)
Definition: SBR.c:215
dai::bootloader::request::BootMemory
Definition: Bootloader.hpp:89
sbr_serialize
int sbr_serialize(const SBR *sbr, void *buffer, uint32_t max_size)
Definition: SBR.c:84
Resources.hpp
dai::logger::get_level
spdlog::level::level_enum get_level()
Definition: Logging.hpp:48
dai::PipelineSchema
Definition: PipelineSchema.hpp:13
dai::bootloader::request::IsUserBootloader
Definition: Bootloader.hpp:248
dai::bootloader::response::FlashComplete
Definition: Bootloader.hpp:282
dai::bootloader::XLINK_CHANNEL_WATCHDOG
constexpr static const char * XLINK_CHANNEL_WATCHDOG
Definition: depthai-bootloader-shared/include/depthai-bootloader-shared/XLinkConstants.hpp:12
dai::DeviceBootloader::lastWatchdogPingTime
std::chrono::steady_clock::time_point lastWatchdogPingTime
Definition: DeviceBootloader.hpp:525
dai::logger::info
void info(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:78
dai::DeviceBootloader::requestVersion
Version requestVersion()
Definition: DeviceBootloader.cpp:607
dai::DeviceBootloader::flashUsbRecoveryBootHeader
std::tuple< bool, std::string > flashUsbRecoveryBootHeader(Memory memory)
Definition: DeviceBootloader.cpp:1058
XLinkConstants.hpp
dai::DeviceBootloader::bootloaderType
Type bootloaderType
Definition: DeviceBootloader.hpp:512
dai::DeviceBootloader::createWatchdog
void createWatchdog()
Definition: DeviceBootloader.cpp:276
dai::bootloader::request::GetBootloaderCommit
Definition: Bootloader.hpp:182
dai::bootloader::getStructure
const Structure getStructure(Type type)
Definition: Structure.hpp:78
dai::DeviceBootloader::flashUserBootloader
std::tuple< bool, std::string > flashUserBootloader(std::function< void(float)> progressCallback, const dai::Path &path={})
Definition: DeviceBootloader.cpp:940
SBR_SECTION::offset
uint32_t offset
Definition: SBR.h:31
dai::bootloader::Structure::offset
std::map< Section, long > offset
Definition: Structure.hpp:19
dai::DeviceBootloader::saveDepthaiApplicationPackage
static void saveDepthaiApplicationPackage(const dai::Path &path, const Pipeline &pipeline, const dai::Path &pathToCmd={}, bool compress=false, std::string applicationName="", bool checkChecksum=false)
Definition: DeviceBootloader.cpp:241
dai::DeviceBootloader::Config::setDnsIPv4
void setDnsIPv4(std::string dns, std::string dnsAlt="")
Set IPv4 DNS options.
Definition: DeviceBootloader.cpp:1520
SBR.h
dai::bootloader::request::ReadFlash::offset
uint32_t offset
Definition: Bootloader.hpp:219
dai::XLinkStream
Definition: XLinkStream.hpp:37
dai::DeviceBootloader::Config::getIPv4Gateway
std::string getIPv4Gateway()
Get IPv4 gateway.
Definition: DeviceBootloader.cpp:1516
dai::DeviceBootloader::Config::getNetworkTimeout
std::chrono::milliseconds getNetworkTimeout()
Get NETWORK timeout.
Definition: DeviceBootloader.cpp:1545
dai::bootloader::request::UpdateFlashBootHeader::gpioMode
int32_t gpioMode
Definition: Bootloader.hpp:206
dai::bootloader::Structure::size
std::map< Section, long > size
Definition: Structure.hpp:19
dai::DeviceBootloader::isEmbedded
bool isEmbedded
Definition: DeviceBootloader.hpp:511
dai::DeviceBootloader::deviceInfo
DeviceInfo deviceInfo
Definition: DeviceBootloader.hpp:509
dai::DeviceBootloader::Config::getIPv4
std::string getIPv4()
Get IPv4.
Definition: DeviceBootloader.cpp:1510
dai::DeviceBootloader::flashConfigData
std::tuple< bool, std::string > flashConfigData(nlohmann::json configData, Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1315
dai::DeviceBootloader::createDepthaiApplicationPackage
static std::vector< uint8_t > createDepthaiApplicationPackage(const Pipeline &pipeline, const dai::Path &pathToCmd={}, bool compress=false, std::string applicationName="", bool checkChecksum=false)
Definition: DeviceBootloader.cpp:72
tl::nullopt
static constexpr nullopt_t nullopt
Represents an empty optional.
Definition: 3rdparty/tl/optional.hpp:663
Structure.hpp
dai::Version
Version structure.
Definition: Version.hpp:8
dai::DeviceBootloader::watchdogThread
std::thread watchdogThread
Definition: DeviceBootloader.hpp:519
dai::logger::debug
void debug(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:72
dai::bootloader::response::Command
Command
Definition: Bootloader.hpp:260
dai::DeviceInfo::state
XLinkDeviceState_t state
Definition: XLinkConnection.hpp:42
dai::DeviceBootloader::getType
Type getType() const
Definition: DeviceBootloader.cpp:638
dai::bootloader::request::GetApplicationDetails
Definition: Bootloader.hpp:226
dai::logger::warn
void warn(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:84
dai::DeviceBootloader::Config
Definition: DeviceBootloader.hpp:39
dai::utility::serialize
bool serialize(const T &obj, std::vector< std::uint8_t > &data)
Definition: Serialization.hpp:38
dai::DeviceBootloader::~DeviceBootloader
~DeviceBootloader()
Destroy the Device Bootloader object.
Definition: DeviceBootloader.cpp:591
dai::Resources::getInstance
static Resources & getInstance()
Definition: Resources.cpp:248
SBR_SECTION::checksum
uint32_t checksum
Definition: SBR.h:32
dai::bootloader::Memory
Memory
Definition: Memory.hpp:11
dai::DeviceBootloader::Config::setDynamicIPv4
void setDynamicIPv4(std::string ip, std::string mask, std::string gateway)
Setting a dynamic IPv4 will set that IP as well as start DHCP client.
Definition: DeviceBootloader.cpp:1499
dai::bootloader::Type
Type
Definition: Type.hpp:11
dai::bootloader::request::UpdateFlashBootHeader
Definition: Bootloader.hpp:194
dai::DeviceBootloader::allowFlashingBootloader
bool allowFlashingBootloader
Definition: DeviceBootloader.hpp:531
DAI_SPAN_NAMESPACE_NAME::detail::data
constexpr auto data(C &c) -> decltype(c.data())
Definition: span.hpp:177
dai::platform::getIPv4AddressAsBinary
uint32_t getIPv4AddressAsBinary(std::string address)
Definition: Platform.cpp:27
dai::DeviceBootloader::flashConfigClear
std::tuple< bool, std::string > flashConfigClear(Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1290
dai::DeviceBootloader::receiveResponseThrow
void receiveResponseThrow(T &response)
Definition: DeviceBootloader.cpp:1477
SBR_SECTION::type
uint8_t type
Definition: SBR.h:33
dai::bootloader::request::SetBootloaderConfig::numPackets
uint32_t numPackets
Definition: Bootloader.hpp:153
dai::DeviceBootloader::init
void init(bool embeddedMvcmd, const dai::Path &pathToMvcmd, tl::optional< bootloader::Type > type, bool allowBlFlash)
Definition: DeviceBootloader.cpp:357
dai::DeviceBootloader::isUserBootloaderSupported
bool isUserBootloaderSupported()
Definition: DeviceBootloader.cpp:711
dai::bootloader::Section::BOOTLOADER_CONFIG
@ BOOTLOADER_CONFIG
dai::DeviceBootloader::monitorThread
std::thread monitorThread
Definition: DeviceBootloader.hpp:523
dai::bootloader::response::BootloaderVersion::minor
uint32_t minor
Definition: Bootloader.hpp:309
Bootloader.hpp
dai::DeviceBootloader::Config::setMacAddress
void setMacAddress(std::string mac)
Set MAC address if not flashed on controller.
Definition: DeviceBootloader.cpp:1557
dai::DeviceBootloader::flashBootHeader
std::tuple< bool, std::string > flashBootHeader(Memory memory, int32_t frequency=-1, int64_t location=-1, int32_t dummyCycles=-1, int64_t offset=-1)
Definition: DeviceBootloader.cpp:1072
dai::DeviceBootloader::receiveResponse
bool receiveResponse(T &response)
Definition: DeviceBootloader.cpp:1464
dai::bootloader::request::SetBootloaderConfig::totalSize
uint32_t totalSize
Definition: Bootloader.hpp:152
dai::DeviceBootloader::lastWatchdogPingTimeMtx
std::mutex lastWatchdogPingTimeMtx
Definition: DeviceBootloader.hpp:524
Device.hpp
dai::bootloader::response::FlashComplete::errorMsg
char errorMsg[64]
Definition: Bootloader.hpp:288
dai::DeviceBootloader::version
Version version
Definition: DeviceBootloader.hpp:534
dai::bootloader::request::UpdateFlashBootHeader::offset
int64_t offset
Definition: Bootloader.hpp:202
SBR::sections
SBR_SECTION sections[SBR_MAX_NUM_SECTIONS]
Definition: SBR.h:52
dai::bootloader::response::BootloaderType::type
Type type
Definition: Bootloader.hpp:321
RawImgFrame.hpp
DeviceBootloader.hpp
dai::DeviceBootloader::watchdogRunning
std::atomic< bool > watchdogRunning
Definition: DeviceBootloader.hpp:520
dai::bootloader::request::UpdateFlashBootHeader::frequency
int32_t frequency
Definition: Bootloader.hpp:205
dai::bootloader::request::UsbRomBoot
Definition: Bootloader.hpp:46
dai::Pipeline::serialize
void serialize(PipelineSchema &schema, Assets &assets, std::vector< std::uint8_t > &assetStorage) const
Definition: Pipeline.hpp:130
dai::bootloader::response::MemoryDetails::memorySize
int64_t memorySize
Definition: Bootloader.hpp:420
dai::bootloader::response::BootloaderVersion
Definition: Bootloader.hpp:303
dai::bootloader::request::GetApplicationDetails::memory
Memory memory
Definition: Bootloader.hpp:231
dai::bootloader::response::FlashStatusUpdate
Definition: Bootloader.hpp:293
dai::DeviceBootloader::getVersion
Version getVersion() const
Definition: DeviceBootloader.cpp:599
dai::DeviceBootloader::flashConfigFile
std::tuple< bool, std::string > flashConfigFile(const dai::Path &configPath, Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1345
DAI_SPAN_NAMESPACE_NAME::detail::size
constexpr auto size(const C &c) -> decltype(c.size())
Definition: span.hpp:167
dai::bootloader::request::GetMemoryDetails
Definition: Bootloader.hpp:237
dai::DeviceBootloader::MemoryInfo::size
std::int64_t size
Definition: DeviceBootloader.hpp:101
dai::bootloader::request::UpdateFlash::totalSize
uint32_t totalSize
Definition: Bootloader.hpp:70
dai::DeviceBootloader::isUserBootloader
bool isUserBootloader()
Definition: DeviceBootloader.cpp:729
dai::DeviceInfo::name
std::string name
Definition: XLinkConnection.hpp:40
dai::bootloader::XLINK_CHANNEL_BOOTLOADER
constexpr static const char * XLINK_CHANNEL_BOOTLOADER
Definition: depthai-bootloader-shared/include/depthai-bootloader-shared/XLinkConstants.hpp:11
dai::bootloader::Type::AUTO
@ AUTO
dai::DeviceBootloader::destroyWatchdog
void destroyWatchdog()
Definition: DeviceBootloader.cpp:349
SBR_COMPRESSION_ZLIB
@ SBR_COMPRESSION_ZLIB
Definition: SBR.h:20
dai::DeviceBootloader::Config::getUsbTimeout
std::chrono::milliseconds getUsbTimeout()
Get USB timeout.
Definition: DeviceBootloader.cpp:1537
SBR_NO_COMPRESSION
@ SBR_NO_COMPRESSION
Definition: SBR.h:19
dai::bootloader::response::BootloaderType
Definition: Bootloader.hpp:316
dai::bootloader::Type::USB
@ USB
dai::DeviceBootloader::DEFAULT_TYPE
static constexpr const Type DEFAULT_TYPE
Default Bootloader type.
Definition: DeviceBootloader.hpp:108
dai::DeviceBootloader::connection
std::shared_ptr< XLinkConnection > connection
Definition: DeviceBootloader.hpp:508
dai::DeviceBootloader::Version
dai::Version Version
Definition: DeviceBootloader.hpp:90
dai::bootloader::request::UpdateFlashEx2::totalSize
uint32_t totalSize
Definition: Bootloader.hpp:124
dai::Resources::getDeviceFirmware
std::vector< std::uint8_t > getDeviceFirmware(bool usb2Mode, OpenVINO::Version version=OpenVINO::VERSION_UNIVERSAL) const
Definition: Resources.cpp:371
SBR_SECTION::size
uint32_t size
Definition: SBR.h:30
dai::bootloader::response::BootloaderCommit
Definition: Bootloader.hpp:367
dai::Pipeline::getDeviceConfig
Device::Config getDeviceConfig() const
Get device configuration needed for this pipeline.
Definition: Pipeline.hpp:308
dai::DeviceBootloader::Config::setStaticIPv4
void setStaticIPv4(std::string ip, std::string mask, std::string gateway)
Setting a static IPv4 won't start DHCP client.
Definition: DeviceBootloader.cpp:1493
Assets.hpp
SBR_SECTION::name
char name[SBR_SECTION_NAME_MAX_SIZE]
Definition: SBR.h:29
dai::bootloader::response::FlashComplete::success
uint32_t success
Definition: Bootloader.hpp:287
SBR
Definition: SBR.h:50
dai::bootloader::request::UpdateFlash::numPackets
uint32_t numPackets
Definition: Bootloader.hpp:71
dai::bootloader::XLINK_WATCHDOG_TIMEOUT
constexpr static const std::chrono::milliseconds XLINK_WATCHDOG_TIMEOUT
Definition: depthai-bootloader-shared/include/depthai-bootloader-shared/XLinkConstants.hpp:18
sbr_section_set_bootable
void sbr_section_set_bootable(SBR_SECTION *sbr_section, bool bootable)
Definition: SBR.c:197
dai::bootloader::request::UpdateFlashBootHeader::dummyCycles
int32_t dummyCycles
Definition: Bootloader.hpp:204
dai::DeviceBootloader::Config::getUsbMaxSpeed
UsbSpeed getUsbMaxSpeed()
Get maxUsbSpeed.
Definition: DeviceBootloader.cpp:1553
dai::DeviceBootloader::sendRequest
bool sendRequest(const T &request)
Definition: DeviceBootloader.cpp:1407
dai::DeviceBootloader::isEmbeddedVersion
bool isEmbeddedVersion() const
Definition: DeviceBootloader.cpp:1398
dai::bootloader::response::IsUserBootloader::isUserBootloader
uint32_t isUserBootloader
Definition: Bootloader.hpp:432
dai::bootloader::response::BootloaderVersion::major
uint32_t major
Definition: Bootloader.hpp:308
dai::Assets
Definition: Assets.hpp:22
dai::DeviceBootloader::readConfigData
nlohmann::json readConfigData(Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1260
nanorpc::core::detail::pack::meta::type
type
Definition: pack_meta.h:26
dai::DeviceBootloader::flashBootloader
std::tuple< bool, std::string > flashBootloader(std::function< void(float)> progressCallback, const dai::Path &path={})
Definition: DeviceBootloader.cpp:854
dai::bootloader::request::SetBootloaderConfig::memory
Memory memory
Definition: Bootloader.hpp:149
Platform.hpp
dai::bootloader::response::GetBootloaderConfig
Definition: Bootloader.hpp:329
dai::bootloader::request::ReadFlash
Definition: Bootloader.hpp:213
Serialization.hpp
dai::DeviceBootloader::receiveResponseData
bool receiveResponseData(std::vector< uint8_t > &data)
Definition: DeviceBootloader.cpp:1442
dai::bootloader::request::GetBootloaderVersion
Definition: Bootloader.hpp:78
dai::DeviceBootloader::Config::data
nlohmann::json data
Definition: DeviceBootloader.hpp:86
dai::DeviceBootloader::getMemoryInfo
MemoryInfo getMemoryInfo(Memory memory)
Definition: DeviceBootloader.cpp:688
sbr_section_set_offset
void sbr_section_set_offset(SBR_SECTION *sbr_section, uint32_t offset)
Definition: SBR.c:182
dai::bootloader::request::UpdateFlashEx2::memory
Memory memory
Definition: Bootloader.hpp:122
dai::bootloader::response::ApplicationDetails
Definition: Bootloader.hpp:395
dai::DeviceBootloader::Config::setUsbMaxSpeed
void setUsbMaxSpeed(UsbSpeed speed)
Set maxUsbSpeed.
Definition: DeviceBootloader.cpp:1549
dai::DeviceBootloader::Config::setNetworkTimeout
void setNetworkTimeout(std::chrono::milliseconds ms)
Set NETWOR timeout.
Definition: DeviceBootloader.cpp:1541
dai::bootloader::request::GetBootloaderConfig::maxSize
uint32_t maxSize
Definition: Bootloader.hpp:166
sbr_section_set_ignore_checksum
void sbr_section_set_ignore_checksum(SBR_SECTION *sbr_section, bool ignore_checksum)
Definition: SBR.c:206
dai::platform::getIPv4AddressAsString
std::string getIPv4AddressAsString(std::uint32_t binary)
Definition: Platform.cpp:47
dai::DeviceBootloader::getEmbeddedBootloaderVersion
static Version getEmbeddedBootloaderVersion()
Definition: DeviceBootloader.cpp:595
dai::bootloader::request::GetBootloaderConfig::memory
Memory memory
Definition: Bootloader.hpp:164
dai::DeviceBootloader::Config::isStaticIPV4
bool isStaticIPV4()
Get if static IPv4 configuration is set.
Definition: DeviceBootloader.cpp:1506
dai::DeviceBootloader::isAllowedFlashingBootloader
bool isAllowedFlashingBootloader() const
Definition: DeviceBootloader.cpp:642
dai::DeviceBootloader::getFirstAvailableDevice
static std::tuple< bool, DeviceInfo > getFirstAvailableDevice()
Definition: DeviceBootloader.cpp:48
tl::optional
Definition: 3rdparty/tl/optional.hpp:120
dai::bootloader::request::GetBootloaderType
Definition: Bootloader.hpp:132
std
Definition: Node.hpp:366
dai::Resources::getBootloaderFirmware
std::vector< std::uint8_t > getBootloaderFirmware(DeviceBootloader::Type type=DeviceBootloader::Type::USB) const
Definition: Resources.cpp:201
dai::DeviceBootloader::stream
std::unique_ptr< XLinkStream > stream
Definition: DeviceBootloader.hpp:528
dai::DeviceBootloader::Config::getDnsIPv4
std::string getDnsIPv4()
Get primary IPv4 DNS server.
Definition: DeviceBootloader.cpp:1525
sbr_section_set_name
void sbr_section_set_name(SBR_SECTION *sbr_section, const char *name)
Definition: SBR.c:172
dai::DeviceBootloader::MemoryInfo::info
std::string info
Definition: DeviceBootloader.hpp:102
dai::DeviceBootloader::Config::getMacAddress
std::string getMacAddress()
Get MAC address if not flashed on controller.
Definition: DeviceBootloader.cpp:1570
dai::DeviceBootloader::MemoryInfo::available
bool available
Definition: DeviceBootloader.hpp:100
dai::DeviceBootloader::getFlashedVersion
tl::optional< Version > getFlashedVersion() const
Definition: DeviceBootloader.cpp:603
dai::DeviceBootloader::flashConfig
std::tuple< bool, std::string > flashConfig(const Config &config, Memory memory=Memory::AUTO, Type type=Type::AUTO)
Definition: DeviceBootloader.cpp:1359
dai::DeviceBootloader::closed
std::atomic< bool > closed
Definition: DeviceBootloader.hpp:516
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::DeviceBootloader::getAllAvailableDevices
static std::vector< DeviceInfo > getAllAvailableDevices()
Definition: DeviceBootloader.cpp:63
spdlog-fmt.hpp
dai::DeviceBootloader::readApplicationInfo
ApplicationInfo readApplicationInfo(Memory memory)
Definition: DeviceBootloader.cpp:655
dai::bootloader::request::SetBootloaderConfig::offset
int64_t offset
Definition: Bootloader.hpp:150
dai::bootloader::request::UpdateFlashEx2
Definition: Bootloader.hpp:117
dai::DeviceBootloader::parseResponse
bool parseResponse(const std::vector< uint8_t > &data, T &response)
Definition: DeviceBootloader.cpp:1450
dai::bootloader::request::UpdateFlashBootHeader::type
Type type
Definition: Bootloader.hpp:201
reset
static void reset(uint32_t digest[], std::string &buffer, uint64_t &transforms)
Definition: sha1.hpp:55
sbr_section_set_checksum
void sbr_section_set_checksum(SBR_SECTION *sbr_section, uint32_t checksum)
Definition: SBR.c:187
dai::bootloader::response::MemoryDetails
Definition: Bootloader.hpp:413
dai::Version::toString
std::string toString() const
Convert Version to string.
Definition: Version.cpp:53
dai::DeviceBootloader::readCustom
std::tuple< bool, std::string > readCustom(Memory memory, size_t offset, size_t size, std::vector< uint8_t > &data, std::function< void(float)> progressCb=nullptr)
Definition: DeviceBootloader.cpp:1190
dai::DeviceBootloader::isClosed
bool isClosed() const
Definition: DeviceBootloader.cpp:587
dai::DeviceInfo::mxid
std::string mxid
Definition: XLinkConnection.hpp:41
dai::bootloader::request::UpdateFlash::storage
Storage storage
Definition: Bootloader.hpp:69
dai::Path
Represents paths on a filesystem; accepts utf-8, Windows utf-16 wchar_t, or std::filesystem::path.
Definition: Path.hpp:27
SBR_RAW_SIZE
#define SBR_RAW_SIZE
Definition: SBR.h:55
dai::bootloader::response::FlashStatusUpdate::progress
float progress
Definition: Bootloader.hpp:298
dai::bootloader::request::GetBootloaderConfig::offset
int64_t offset
Definition: Bootloader.hpp:165
dai::DeviceBootloader::sendRequestThrow
void sendRequestThrow(const T &request)
Definition: DeviceBootloader.cpp:1426
dai::DeviceBootloader::flashClear
std::tuple< bool, std::string > flashClear(Memory memory=Memory::AUTO)
Definition: DeviceBootloader.cpp:846
dai::DeviceBootloader::flashCustom
std::tuple< bool, std::string > flashCustom(Memory memory, size_t offset, const std::vector< uint8_t > &data, std::function< void(float)> progressCb=nullptr)
Definition: DeviceBootloader.cpp:1112
dai::DeviceBootloader::ApplicationInfo
Definition: DeviceBootloader.hpp:92
Logging.hpp
dai::bootloader::request::UpdateFlash
Definition: Bootloader.hpp:63
dai::DeviceBootloader::flashDepthaiApplicationPackage
std::tuple< bool, std::string > flashDepthaiApplicationPackage(std::function< void(float)> progressCallback, std::vector< uint8_t > package, Memory memory=Memory::AUTO)
Definition: DeviceBootloader.cpp:746
dai::DeviceBootloader::Config::getIPv4Mask
std::string getIPv4Mask()
Get IPv4 mask.
Definition: DeviceBootloader.cpp:1513
dai
Definition: CameraExposureOffset.hpp:6
dai::bootloader::request::SetBootloaderConfig
Definition: Bootloader.hpp:144
dai::DeviceBootloader::flash
std::tuple< bool, std::string > flash(std::function< void(float)> progressCallback, const Pipeline &pipeline, bool compress=false, std::string applicationName="", Memory memory=Memory::AUTO, bool checkChecksum=false)
Definition: DeviceBootloader.cpp:646
dai::DeviceBootloader::flashedVersion
tl::optional< Version > flashedVersion
Definition: DeviceBootloader.hpp:513
dai::DeviceBootloader::bootMemory
void bootMemory(const std::vector< uint8_t > &fw)
Definition: DeviceBootloader.cpp:1364
dai::DeviceBootloader::flashFastBootHeader
std::tuple< bool, std::string > flashFastBootHeader(Memory memory, int32_t frequency=-1, int64_t location=-1, int32_t dummyCycles=-1, int64_t offset=-1)
Definition: DeviceBootloader.cpp:1092
dai::DeviceBootloader::DeviceBootloader
DeviceBootloader()=delete
dai::DeviceBootloader::getEmbeddedBootloaderBinary
static std::vector< std::uint8_t > getEmbeddedBootloaderBinary(Type type=DEFAULT_TYPE)
Definition: DeviceBootloader.cpp:1402
dai::DeviceBootloader::Type
dai::bootloader::Type Type
Definition: DeviceBootloader.hpp:32
dai::bootloader::response::IsUserBootloader
Definition: Bootloader.hpp:427
dai::bootloader::response::GetBootloaderConfig::errorMsg
char errorMsg[64]
Definition: Bootloader.hpp:335
dai::DeviceBootloader::Config::setUsbTimeout
void setUsbTimeout(std::chrono::milliseconds ms)
Set USB timeout.
Definition: DeviceBootloader.cpp:1533
dai::bootloader::response::BootloaderVersion::patch
uint32_t patch
Definition: Bootloader.hpp:310


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