Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
dai::DeviceBootloader Class Reference

#include <DeviceBootloader.hpp>

Classes

struct  ApplicationInfo
 
struct  Config
 
struct  MemoryInfo
 

Public Types

using Memory = dai::bootloader::Memory
 
using NetworkConfig = dai::bootloader::NetworkConfig
 
using Section = dai::bootloader::Section
 
using Type = dai::bootloader::Type
 
using UsbConfig = dai::bootloader::UsbConfig
 
using Version = dai::Version
 

Public Member Functions

void bootMemory (const std::vector< uint8_t > &fw)
 
void bootUsbRomBootloader ()
 
void close ()
 
 DeviceBootloader ()=delete
 
 DeviceBootloader (const DeviceInfo &devInfo)
 
template<>
 DeviceBootloader (const DeviceInfo &devInfo, bool allowFlashingBootloader)
 
 DeviceBootloader (const DeviceInfo &devInfo, const dai::Path &pathToBootloader, bool allowFlashingBootloader=false)
 
template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
 DeviceBootloader (const DeviceInfo &devInfo, T allowFlashingBootloader)
 
 DeviceBootloader (const DeviceInfo &devInfo, Type type, bool allowFlashingBootloader=false)
 
 DeviceBootloader (std::string nameOrDeviceId, bool allowFlashingBootloader=false)
 
std::tuple< bool, std::string > flash (const Pipeline &pipeline, bool compress=false, std::string applicationName="", Memory memory=Memory::AUTO, bool checkChecksum=false)
 
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)
 
std::tuple< bool, std::string > flashBootHeader (Memory memory, int32_t frequency=-1, int64_t location=-1, int32_t dummyCycles=-1, int64_t offset=-1)
 
std::tuple< bool, std::string > flashBootloader (Memory memory, Type type, std::function< void(float)> progressCallback, const dai::Path &path={})
 
std::tuple< bool, std::string > flashBootloader (std::function< void(float)> progressCallback, const dai::Path &path={})
 
std::tuple< bool, std::string > flashClear (Memory memory=Memory::AUTO)
 
std::tuple< bool, std::string > flashConfig (const Config &config, Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
std::tuple< bool, std::string > flashConfigClear (Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
std::tuple< bool, std::string > flashConfigData (nlohmann::json configData, Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
std::tuple< bool, std::string > flashConfigFile (const dai::Path &configPath, Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
std::tuple< bool, std::string > flashCustom (Memory memory, size_t offset, const std::vector< uint8_t > &data, std::function< void(float)> progressCb=nullptr)
 
std::tuple< bool, std::string > flashCustom (Memory memory, size_t offset, const uint8_t *data, size_t size, std::function< void(float)> progressCb=nullptr)
 
std::tuple< bool, std::string > flashCustom (Memory memory, size_t offset, std::string filename, std::function< void(float)> progressCb=nullptr)
 
std::tuple< bool, std::string > flashDepthaiApplicationPackage (std::function< void(float)> progressCallback, std::vector< uint8_t > package, Memory memory=Memory::AUTO)
 
std::tuple< bool, std::string > flashDepthaiApplicationPackage (std::vector< uint8_t > package, Memory memory=Memory::AUTO)
 
std::tuple< bool, std::string > flashFastBootHeader (Memory memory, int32_t frequency=-1, int64_t location=-1, int32_t dummyCycles=-1, int64_t offset=-1)
 
std::tuple< bool, std::string > flashGpioModeBootHeader (Memory memory, int gpioMode)
 
std::tuple< bool, std::string > flashUsbRecoveryBootHeader (Memory memory)
 
std::tuple< bool, std::string > flashUserBootloader (std::function< void(float)> progressCallback, const dai::Path &path={})
 
tl::optional< VersiongetFlashedVersion () const
 
MemoryInfo getMemoryInfo (Memory memory)
 
Type getType () const
 
Version getVersion () const
 
bool isAllowedFlashingBootloader () const
 
bool isClosed () const
 
bool isEmbeddedVersion () const
 
bool isUserBootloader ()
 
bool isUserBootloaderSupported ()
 
ApplicationInfo readApplicationInfo (Memory memory)
 
Config readConfig (Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
nlohmann::json readConfigData (Memory memory=Memory::AUTO, Type type=Type::AUTO)
 
std::tuple< bool, std::string, std::vector< uint8_t > > readCustom (Memory memory, size_t offset, size_t size, std::function< void(float)> progressCb=nullptr)
 
std::tuple< bool, std::string > readCustom (Memory memory, size_t offset, size_t size, std::string filename, std::function< void(float)> progressCb=nullptr)
 
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)
 
std::tuple< bool, std::string > readCustom (Memory memory, size_t offset, size_t size, uint8_t *data, std::function< void(float)> progressCb=nullptr)
 
 ~DeviceBootloader ()
 Destroy the Device Bootloader object. More...
 

Static Public Member Functions

static std::vector< uint8_t > createDepthaiApplicationPackage (const Pipeline &pipeline, bool compress, std::string applicationName="", bool checkChecksum=false)
 
static std::vector< uint8_t > createDepthaiApplicationPackage (const Pipeline &pipeline, const dai::Path &pathToCmd={}, bool compress=false, std::string applicationName="", bool checkChecksum=false)
 
static std::vector< DeviceInfogetAllAvailableDevices ()
 
static std::vector< std::uint8_t > getEmbeddedBootloaderBinary (Type type=DEFAULT_TYPE)
 
static Version getEmbeddedBootloaderVersion ()
 
static std::tuple< bool, DeviceInfogetFirstAvailableDevice ()
 
static void saveDepthaiApplicationPackage (const dai::Path &path, const Pipeline &pipeline, bool compress, std::string applicationName="", bool checkChecksum=false)
 
static void saveDepthaiApplicationPackage (const dai::Path &path, const Pipeline &pipeline, const dai::Path &pathToCmd={}, bool compress=false, std::string applicationName="", bool checkChecksum=false)
 

Static Public Attributes

static constexpr const Type DEFAULT_TYPE {Type::USB}
 Default Bootloader type. More...
 

Private Member Functions

void createWatchdog ()
 
void destroyWatchdog ()
 
std::tuple< bool, std::string > flashCustom (Memory memory, size_t offset, const uint8_t *data, size_t size, std::string filename, std::function< void(float)> progressCb)
 
void init (bool embeddedMvcmd, const dai::Path &pathToMvcmd, tl::optional< bootloader::Type > type, bool allowBlFlash)
 
template<typename T >
bool parseResponse (const std::vector< uint8_t > &data, T &response)
 
std::tuple< bool, std::string > readCustom (Memory memory, size_t offset, size_t size, uint8_t *data, std::string filename, std::function< void(float)> progressCb)
 
template<typename T >
bool receiveResponse (T &response)
 
bool receiveResponseData (std::vector< uint8_t > &data)
 
template<typename T >
void receiveResponseThrow (T &response)
 
Version requestVersion ()
 
template<typename T >
bool sendRequest (const T &request)
 
template<typename T >
void sendRequestThrow (const T &request)
 

Private Attributes

bool allowFlashingBootloader = false
 
Type bootloaderType
 
std::atomic< bool > closed {false}
 
std::shared_ptr< XLinkConnectionconnection
 
DeviceInfo deviceInfo = {}
 
tl::optional< VersionflashedVersion
 
bool isEmbedded = false
 
std::chrono::steady_clock::time_point lastWatchdogPingTime
 
std::mutex lastWatchdogPingTimeMtx
 
std::thread monitorThread
 
std::unique_ptr< XLinkStreamstream
 
Version version {0, 0, 2}
 
std::atomic< bool > watchdogRunning {true}
 
std::thread watchdogThread
 

Detailed Description

Represents the DepthAI bootloader with the methods to interact with it.

Definition at line 29 of file DeviceBootloader.hpp.

Member Typedef Documentation

◆ Memory

Definition at line 33 of file DeviceBootloader.hpp.

◆ NetworkConfig

Definition at line 36 of file DeviceBootloader.hpp.

◆ Section

Definition at line 34 of file DeviceBootloader.hpp.

◆ Type

Definition at line 32 of file DeviceBootloader.hpp.

◆ UsbConfig

Definition at line 35 of file DeviceBootloader.hpp.

◆ Version

Definition at line 90 of file DeviceBootloader.hpp.

Constructor & Destructor Documentation

◆ DeviceBootloader() [1/7]

dai::DeviceBootloader::DeviceBootloader ( )
delete

◆ DeviceBootloader() [2/7]

dai::DeviceBootloader::DeviceBootloader ( const DeviceInfo devInfo)
explicit

Connects to or boots device in bootloader mode depending on devInfo state; flashing not allowed

Parameters
devInfoDeviceInfo of which to boot or connect to

Definition at line 255 of file DeviceBootloader.cpp.

◆ DeviceBootloader() [3/7]

template<typename T , std::enable_if_t< std::is_same< T, bool >::value, bool > = true>
dai::DeviceBootloader::DeviceBootloader ( const DeviceInfo devInfo,
allowFlashingBootloader 
)

Connects to or boots device in bootloader mode depending on devInfo state.

Parameters
devInfoDeviceInfo of which to boot or connect to
allowFlashingBootloader(bool) Set to true to allow flashing the devices bootloader

◆ DeviceBootloader() [4/7]

dai::DeviceBootloader::DeviceBootloader ( const DeviceInfo devInfo,
Type  type,
bool  allowFlashingBootloader = false 
)

Connects to device in bootloader of specified type. Throws if it wasn't possible. This constructor will automatically boot into specified bootloader type if not already running

Parameters
devInfoDeviceInfo of which to boot or connect to
typeType of bootloader to boot/connect to.
allowFlashingBootloaderSet to true to allow flashing the devices bootloader. Defaults to false

Definition at line 264 of file DeviceBootloader.cpp.

◆ DeviceBootloader() [5/7]

dai::DeviceBootloader::DeviceBootloader ( const DeviceInfo devInfo,
const dai::Path pathToBootloader,
bool  allowFlashingBootloader = false 
)

Connects to or boots device in bootloader mode depending on devInfo state with a custom bootloader firmware.

Parameters
devInfoDeviceInfo of which to boot or connect to
pathToBootloaderCustom bootloader firmware to boot
allowFlashingBootloaderSet to true to allow flashing the devices bootloader. Defaults to false

Definition at line 268 of file DeviceBootloader.cpp.

◆ DeviceBootloader() [6/7]

dai::DeviceBootloader::DeviceBootloader ( std::string  nameOrDeviceId,
bool  allowFlashingBootloader = false 
)

Connects to device with specified name/device id

Parameters
nameOrDeviceIdCreates DeviceInfo with nameOrDeviceId to connect to
allowFlashingBootloaderSet to true to allow flashing the devices bootloader. Defaults to false

Definition at line 272 of file DeviceBootloader.cpp.

◆ ~DeviceBootloader()

dai::DeviceBootloader::~DeviceBootloader ( )

Destroy the Device Bootloader object.

Definition at line 591 of file DeviceBootloader.cpp.

◆ DeviceBootloader() [7/7]

template<>
dai::DeviceBootloader::DeviceBootloader ( const DeviceInfo devInfo,
bool  allowFlashingBootloader 
)

Definition at line 260 of file DeviceBootloader.cpp.

Member Function Documentation

◆ bootMemory()

void dai::DeviceBootloader::bootMemory ( const std::vector< uint8_t > &  fw)

Boots a custom FW in memory

Parameters
fw
Exceptions
Aruntime exception if there are any communication issues

Definition at line 1364 of file DeviceBootloader.cpp.

◆ bootUsbRomBootloader()

void dai::DeviceBootloader::bootUsbRomBootloader ( )

Boots into integrated ROM bootloader in USB mode

Exceptions
Aruntime exception if there are any communication issues

Definition at line 1384 of file DeviceBootloader.cpp.

◆ close()

void dai::DeviceBootloader::close ( )

Explicitly closes connection to device.

Note
This function does not need to be explicitly called as destructor closes the device automatically

Definition at line 558 of file DeviceBootloader.cpp.

◆ createDepthaiApplicationPackage() [1/2]

std::vector< uint8_t > dai::DeviceBootloader::createDepthaiApplicationPackage ( const Pipeline pipeline,
bool  compress,
std::string  applicationName = "",
bool  checkChecksum = false 
)
static

Creates application package which can be flashed to depthai device.

Parameters
pipelinePipeline from which to create the application package
compressSpecifies if contents should be compressed
applicationNameName the application that is flashed
Returns
Depthai application package

Definition at line 234 of file DeviceBootloader.cpp.

◆ createDepthaiApplicationPackage() [2/2]

std::vector< uint8_t > dai::DeviceBootloader::createDepthaiApplicationPackage ( const Pipeline pipeline,
const dai::Path pathToCmd = {},
bool  compress = false,
std::string  applicationName = "",
bool  checkChecksum = false 
)
static

Creates application package which can be flashed to depthai device.

Parameters
pipelinePipeline from which to create the application package
pathToCmdOptional path to custom device firmware
compressOptional boolean which specifies if contents should be compressed
applicationNameOptional name the application that is flashed
Returns
Depthai application package

Definition at line 72 of file DeviceBootloader.cpp.

◆ createWatchdog()

void dai::DeviceBootloader::createWatchdog ( )
private

Definition at line 276 of file DeviceBootloader.cpp.

◆ destroyWatchdog()

void dai::DeviceBootloader::destroyWatchdog ( )
private

Definition at line 349 of file DeviceBootloader.cpp.

◆ flash() [1/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flash ( const Pipeline pipeline,
bool  compress = false,
std::string  applicationName = "",
Memory  memory = Memory::AUTO,
bool  checkChecksum = false 
)

Flashes a given pipeline to the device.

Parameters
pipelinePipeline to flash to the board
compressCompresses application to reduce needed memory size
applicationNameOptional name the application that is flashed

Definition at line 651 of file DeviceBootloader.cpp.

◆ flash() [2/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flash ( std::function< void(float)>  progressCallback,
const Pipeline pipeline,
bool  compress = false,
std::string  applicationName = "",
Memory  memory = Memory::AUTO,
bool  checkChecksum = false 
)

Flashes a given pipeline to the device.

Parameters
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
pipelinePipeline to flash to the board
compressCompresses application to reduce needed memory size
applicationNameName the application that is flashed

Definition at line 646 of file DeviceBootloader.cpp.

◆ flashBootHeader()

std::tuple< bool, std::string > dai::DeviceBootloader::flashBootHeader ( Memory  memory,
int32_t  frequency = -1,
int64_t  location = -1,
int32_t  dummyCycles = -1,
int64_t  offset = -1 
)

Flash optimized boot header

Parameters
memoryWhich memory to flasht the header to
frequencySPI specific parameter, frequency in MHz
locationTarget location the header should boot to. Default to location of bootloader
dummyCyclesSPI specific parameter
offsetOffset in memory to flash the header to. Defaults to offset of boot header
Returns
status as std::tuple<bool, std::string>

Definition at line 1072 of file DeviceBootloader.cpp.

◆ flashBootloader() [1/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flashBootloader ( Memory  memory,
Type  type,
std::function< void(float)>  progressCallback,
const dai::Path path = {} 
)

Flash selected bootloader to the current board

Parameters
memoryMemory to flash
typeBootloader type to flash
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
pathOptional parameter to custom bootloader to flash

Definition at line 858 of file DeviceBootloader.cpp.

◆ flashBootloader() [2/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flashBootloader ( std::function< void(float)>  progressCallback,
const dai::Path path = {} 
)

Flashes bootloader to the current board

Parameters
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
pathOptional parameter to custom bootloader to flash

Definition at line 854 of file DeviceBootloader.cpp.

◆ flashClear()

std::tuple< bool, std::string > dai::DeviceBootloader::flashClear ( Memory  memory = Memory::AUTO)

Clears flashed application on the device, by removing SBR boot structure Doesn't remove fast boot header capability to still boot the application

Definition at line 846 of file DeviceBootloader.cpp.

◆ flashConfig()

std::tuple< bool, std::string > dai::DeviceBootloader::flashConfig ( const Config config,
Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Flashes configuration to bootloader

Parameters
configDataConfiguration structure
memoryOptional - to which memory flash configuration
typeOptional - for which type of bootloader to flash configuration

Definition at line 1359 of file DeviceBootloader.cpp.

◆ flashConfigClear()

std::tuple< bool, std::string > dai::DeviceBootloader::flashConfigClear ( Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Clears configuration data

Parameters
memoryOptional - on which memory to clear configuration data
typeOptional - for which type of bootloader to clear configuration data

Definition at line 1290 of file DeviceBootloader.cpp.

◆ flashConfigData()

std::tuple< bool, std::string > dai::DeviceBootloader::flashConfigData ( nlohmann::json  configData,
Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Flashes configuration data to bootloader

Parameters
configDataUnstructured configuration data
memoryOptional - to which memory flash configuration
typeOptional - for which type of bootloader to flash configuration

Definition at line 1315 of file DeviceBootloader.cpp.

◆ flashConfigFile()

std::tuple< bool, std::string > dai::DeviceBootloader::flashConfigFile ( const dai::Path configPath,
Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Flashes configuration data to bootloader

Parameters
configPathUnstructured configuration data
memoryOptional - to which memory flash configuration
typeOptional - for which type of bootloader to flash configuration

Definition at line 1345 of file DeviceBootloader.cpp.

◆ flashCustom() [1/4]

std::tuple< bool, std::string > dai::DeviceBootloader::flashCustom ( Memory  memory,
size_t  offset,
const std::vector< uint8_t > &  data,
std::function< void(float)>  progressCb = nullptr 
)

Flash arbitrary data at custom offset in specified memory

Parameters
memoryMemory to flash
offsetOffset at which to flash the given data in bytes
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
dataData to flash

Definition at line 1112 of file DeviceBootloader.cpp.

◆ flashCustom() [2/4]

std::tuple< bool, std::string > dai::DeviceBootloader::flashCustom ( Memory  memory,
size_t  offset,
const uint8_t *  data,
size_t  size,
std::function< void(float)>  progressCb = nullptr 
)

Definition at line 1121 of file DeviceBootloader.cpp.

◆ flashCustom() [3/4]

std::tuple< bool, std::string > dai::DeviceBootloader::flashCustom ( Memory  memory,
size_t  offset,
const uint8_t *  data,
size_t  size,
std::string  filename,
std::function< void(float)>  progressCb 
)
private

Definition at line 1131 of file DeviceBootloader.cpp.

◆ flashCustom() [4/4]

std::tuple< bool, std::string > dai::DeviceBootloader::flashCustom ( Memory  memory,
size_t  offset,
std::string  filename,
std::function< void(float)>  progressCb = nullptr 
)

Definition at line 1128 of file DeviceBootloader.cpp.

◆ flashDepthaiApplicationPackage() [1/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flashDepthaiApplicationPackage ( std::function< void(float)>  progressCallback,
std::vector< uint8_t >  package,
Memory  memory = Memory::AUTO 
)

Flashes a specific depthai application package that was generated using createDepthaiApplicationPackage or saveDepthaiApplicationPackage

Parameters
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
packageDepthai application package to flash to the board

Definition at line 746 of file DeviceBootloader.cpp.

◆ flashDepthaiApplicationPackage() [2/2]

std::tuple< bool, std::string > dai::DeviceBootloader::flashDepthaiApplicationPackage ( std::vector< uint8_t >  package,
Memory  memory = Memory::AUTO 
)

Flashes a specific depthai application package that was generated using createDepthaiApplicationPackage or saveDepthaiApplicationPackage

Parameters
packageDepthai application package to flash to the board

Definition at line 842 of file DeviceBootloader.cpp.

◆ flashFastBootHeader()

std::tuple< bool, std::string > dai::DeviceBootloader::flashFastBootHeader ( Memory  memory,
int32_t  frequency = -1,
int64_t  location = -1,
int32_t  dummyCycles = -1,
int64_t  offset = -1 
)

Flash fast boot header. Application must already be present in flash, or location must be specified manually. Note - Can soft brick your device if firmware location changes.

Parameters
memoryWhich memory to flash the header to
frequencySPI specific parameter, frequency in MHz
locationTarget location the header should boot to. Default to location of bootloader
dummyCyclesSPI specific parameter
offsetOffset in memory to flash the header to. Defaults to offset of boot header
Returns
status as std::tuple<bool, std::string>

Definition at line 1092 of file DeviceBootloader.cpp.

◆ flashGpioModeBootHeader()

std::tuple< bool, std::string > dai::DeviceBootloader::flashGpioModeBootHeader ( Memory  memory,
int  gpioMode 
)

Flash boot header which boots same as equivalent GPIO mode would

Parameters
gpioModeGPIO mode equivalent

Definition at line 1043 of file DeviceBootloader.cpp.

◆ flashUsbRecoveryBootHeader()

std::tuple< bool, std::string > dai::DeviceBootloader::flashUsbRecoveryBootHeader ( Memory  memory)

Flash USB recovery boot header. Switches to USB ROM Bootloader

Parameters
memoryWhich memory to flash the header to

Definition at line 1058 of file DeviceBootloader.cpp.

◆ flashUserBootloader()

std::tuple< bool, std::string > dai::DeviceBootloader::flashUserBootloader ( std::function< void(float)>  progressCallback,
const dai::Path path = {} 
)

Flashes user bootloader to the current board. Available for NETWORK bootloader type

Parameters
progressCallbackCallback that sends back a value between 0..1 which signifies current flashing progress
pathOptional parameter to custom bootloader to flash

Definition at line 940 of file DeviceBootloader.cpp.

◆ getAllAvailableDevices()

std::vector< DeviceInfo > dai::DeviceBootloader::getAllAvailableDevices ( )
static

Searches for connected devices in either UNBOOTED or BOOTLOADER states.

Returns
Vector of all found devices

Definition at line 63 of file DeviceBootloader.cpp.

◆ getEmbeddedBootloaderBinary()

std::vector< std::uint8_t > dai::DeviceBootloader::getEmbeddedBootloaderBinary ( Type  type = DEFAULT_TYPE)
static
Returns
Embedded bootloader binary

Definition at line 1402 of file DeviceBootloader.cpp.

◆ getEmbeddedBootloaderVersion()

DeviceBootloader::Version dai::DeviceBootloader::getEmbeddedBootloaderVersion ( )
static
Returns
Embedded bootloader version

Definition at line 595 of file DeviceBootloader.cpp.

◆ getFirstAvailableDevice()

std::tuple< bool, DeviceInfo > dai::DeviceBootloader::getFirstAvailableDevice ( )
static

Searches for connected devices in either UNBOOTED or BOOTLOADER states and returns first available.

Returns
Tuple of boolean and DeviceInfo. If found boolean is true and DeviceInfo describes the device. Otherwise false

Definition at line 48 of file DeviceBootloader.cpp.

◆ getFlashedVersion()

tl::optional< DeviceBootloader::Version > dai::DeviceBootloader::getFlashedVersion ( ) const
Returns
Version of the bootloader that is flashed on the device. Nullopt when the version could not be retrieved because the device was in X_LINK_UNBOOTED state before booting the bootloader.

Definition at line 603 of file DeviceBootloader.cpp.

◆ getMemoryInfo()

DeviceBootloader::MemoryInfo dai::DeviceBootloader::getMemoryInfo ( Memory  memory)

Retrieves information about specified memory

Parameters
memorySpecifies which memory to query

Definition at line 688 of file DeviceBootloader.cpp.

◆ getType()

DeviceBootloader::Type dai::DeviceBootloader::getType ( ) const
Returns
Type of currently connected bootloader

Definition at line 638 of file DeviceBootloader.cpp.

◆ getVersion()

DeviceBootloader::Version dai::DeviceBootloader::getVersion ( ) const
Returns
Version of current running bootloader

Definition at line 599 of file DeviceBootloader.cpp.

◆ init()

void dai::DeviceBootloader::init ( bool  embeddedMvcmd,
const dai::Path pathToMvcmd,
tl::optional< bootloader::Type type,
bool  allowBlFlash 
)
private

Definition at line 357 of file DeviceBootloader.cpp.

◆ isAllowedFlashingBootloader()

bool dai::DeviceBootloader::isAllowedFlashingBootloader ( ) const
Returns
True if allowed to flash bootloader

Definition at line 642 of file DeviceBootloader.cpp.

◆ isClosed()

bool dai::DeviceBootloader::isClosed ( ) const

Is the device already closed (or disconnected)

Warning
This function is thread-unsafe and may return outdated incorrect values. It is only meant for use in simple single-threaded code. Well written code should handle exceptions when calling any DepthAI apis to handle hardware events and multithreaded use.

Definition at line 587 of file DeviceBootloader.cpp.

◆ isEmbeddedVersion()

bool dai::DeviceBootloader::isEmbeddedVersion ( ) const
Returns
True when bootloader was booted using latest bootloader integrated in the library. False when bootloader is already running on the device and just connected to.

Definition at line 1398 of file DeviceBootloader.cpp.

◆ isUserBootloader()

bool dai::DeviceBootloader::isUserBootloader ( )

Retrieves whether current bootloader is User Bootloader (B out of A/B configuration)

Definition at line 729 of file DeviceBootloader.cpp.

◆ isUserBootloaderSupported()

bool dai::DeviceBootloader::isUserBootloaderSupported ( )

Checks whether User Bootloader is supported with current bootloader

Returns
true of User Bootloader is supported, false otherwise

Definition at line 711 of file DeviceBootloader.cpp.

◆ parseResponse()

template<typename T >
bool dai::DeviceBootloader::parseResponse ( const std::vector< uint8_t > &  data,
T &  response 
)
private

Definition at line 1450 of file DeviceBootloader.cpp.

◆ readApplicationInfo()

DeviceBootloader::ApplicationInfo dai::DeviceBootloader::readApplicationInfo ( Memory  memory)

Reads information about flashed application in specified memory from device

Parameters
memorySpecifies which memory to query

Definition at line 655 of file DeviceBootloader.cpp.

◆ readConfig()

DeviceBootloader::Config dai::DeviceBootloader::readConfig ( Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Reads configuration from bootloader

Parameters
memoryOptional - from which memory to read configuration
typeOptional - from which type of bootloader to read configuration
Returns
Configuration structure

Definition at line 1354 of file DeviceBootloader.cpp.

◆ readConfigData()

nlohmann::json dai::DeviceBootloader::readConfigData ( Memory  memory = Memory::AUTO,
Type  type = Type::AUTO 
)

Reads configuration data from bootloader

Returns
Unstructured configuration data
Parameters
memoryOptional - from which memory to read configuration data
typeOptional - from which type of bootloader to read configuration data

Definition at line 1260 of file DeviceBootloader.cpp.

◆ readCustom() [1/5]

std::tuple< bool, std::string, std::vector< uint8_t > > dai::DeviceBootloader::readCustom ( Memory  memory,
size_t  offset,
size_t  size,
std::function< void(float)>  progressCb = nullptr 
)

Definition at line 1205 of file DeviceBootloader.cpp.

◆ readCustom() [2/5]

std::tuple< bool, std::string > dai::DeviceBootloader::readCustom ( Memory  memory,
size_t  offset,
size_t  size,
std::string  filename,
std::function< void(float)>  progressCb = nullptr 
)

Definition at line 1201 of file DeviceBootloader.cpp.

◆ readCustom() [3/5]

std::tuple< bool, std::string > dai::DeviceBootloader::readCustom ( Memory  memory,
size_t  offset,
size_t  size,
std::vector< uint8_t > &  data,
std::function< void(float)>  progressCb = nullptr 
)

Reads arbitrary data at custom offset in specified memory

Parameters
memoryMemory to read
offsetOffset at which to read the specified bytes
sizeNumber of bytes to read
dataData to read to. Must be at least 'size' number of bytes big
progressCallbackCallback that sends back a value between 0..1 which signifies current reading progress

Definition at line 1190 of file DeviceBootloader.cpp.

◆ readCustom() [4/5]

std::tuple< bool, std::string > dai::DeviceBootloader::readCustom ( Memory  memory,
size_t  offset,
size_t  size,
uint8_t *  data,
std::function< void(float)>  progressCb = nullptr 
)

Definition at line 1198 of file DeviceBootloader.cpp.

◆ readCustom() [5/5]

std::tuple< bool, std::string > dai::DeviceBootloader::readCustom ( Memory  memory,
size_t  offset,
size_t  size,
uint8_t *  data,
std::string  filename,
std::function< void(float)>  progressCb 
)
private

Definition at line 1214 of file DeviceBootloader.cpp.

◆ receiveResponse()

template<typename T >
bool dai::DeviceBootloader::receiveResponse ( T &  response)
private

Definition at line 1464 of file DeviceBootloader.cpp.

◆ receiveResponseData()

bool dai::DeviceBootloader::receiveResponseData ( std::vector< uint8_t > &  data)
private

Definition at line 1442 of file DeviceBootloader.cpp.

◆ receiveResponseThrow()

template<typename T >
void dai::DeviceBootloader::receiveResponseThrow ( T &  response)
private

Definition at line 1477 of file DeviceBootloader.cpp.

◆ requestVersion()

DeviceBootloader::Version dai::DeviceBootloader::requestVersion ( )
private

Definition at line 607 of file DeviceBootloader.cpp.

◆ saveDepthaiApplicationPackage() [1/2]

void dai::DeviceBootloader::saveDepthaiApplicationPackage ( const dai::Path path,
const Pipeline pipeline,
bool  compress,
std::string  applicationName = "",
bool  checkChecksum = false 
)
static

Saves application package to a file which can be flashed to depthai device.

Parameters
pathPath where to save the application package
pipelinePipeline from which to create the application package
compressSpecifies if contents should be compressed
applicationNameOptional name the application that is flashed

Definition at line 248 of file DeviceBootloader.cpp.

◆ saveDepthaiApplicationPackage() [2/2]

void dai::DeviceBootloader::saveDepthaiApplicationPackage ( const dai::Path path,
const Pipeline pipeline,
const dai::Path pathToCmd = {},
bool  compress = false,
std::string  applicationName = "",
bool  checkChecksum = false 
)
static

Saves application package to a file which can be flashed to depthai device.

Parameters
pathPath where to save the application package
pipelinePipeline from which to create the application package
pathToCmdOptional path to custom device firmware
compressOptional boolean which specifies if contents should be compressed
applicationNameOptional name the application that is flashed

Definition at line 241 of file DeviceBootloader.cpp.

◆ sendRequest()

template<typename T >
bool dai::DeviceBootloader::sendRequest ( const T &  request)
private

Definition at line 1407 of file DeviceBootloader.cpp.

◆ sendRequestThrow()

template<typename T >
void dai::DeviceBootloader::sendRequestThrow ( const T &  request)
private

Definition at line 1426 of file DeviceBootloader.cpp.

Member Data Documentation

◆ allowFlashingBootloader

bool dai::DeviceBootloader::allowFlashingBootloader = false
private

Definition at line 531 of file DeviceBootloader.hpp.

◆ bootloaderType

Type dai::DeviceBootloader::bootloaderType
private

Definition at line 512 of file DeviceBootloader.hpp.

◆ closed

std::atomic<bool> dai::DeviceBootloader::closed {false}
private

Definition at line 516 of file DeviceBootloader.hpp.

◆ connection

std::shared_ptr<XLinkConnection> dai::DeviceBootloader::connection
private

Definition at line 508 of file DeviceBootloader.hpp.

◆ DEFAULT_TYPE

constexpr const DeviceBootloader::Type dai::DeviceBootloader::DEFAULT_TYPE {Type::USB}
staticconstexpr

Default Bootloader type.

Definition at line 108 of file DeviceBootloader.hpp.

◆ deviceInfo

DeviceInfo dai::DeviceBootloader::deviceInfo = {}
private

Definition at line 509 of file DeviceBootloader.hpp.

◆ flashedVersion

tl::optional<Version> dai::DeviceBootloader::flashedVersion
private

Definition at line 513 of file DeviceBootloader.hpp.

◆ isEmbedded

bool dai::DeviceBootloader::isEmbedded = false
private

Definition at line 511 of file DeviceBootloader.hpp.

◆ lastWatchdogPingTime

std::chrono::steady_clock::time_point dai::DeviceBootloader::lastWatchdogPingTime
private

Definition at line 525 of file DeviceBootloader.hpp.

◆ lastWatchdogPingTimeMtx

std::mutex dai::DeviceBootloader::lastWatchdogPingTimeMtx
private

Definition at line 524 of file DeviceBootloader.hpp.

◆ monitorThread

std::thread dai::DeviceBootloader::monitorThread
private

Definition at line 523 of file DeviceBootloader.hpp.

◆ stream

std::unique_ptr<XLinkStream> dai::DeviceBootloader::stream
private

Definition at line 528 of file DeviceBootloader.hpp.

◆ version

Version dai::DeviceBootloader::version {0, 0, 2}
private

Definition at line 534 of file DeviceBootloader.hpp.

◆ watchdogRunning

std::atomic<bool> dai::DeviceBootloader::watchdogRunning {true}
private

Definition at line 520 of file DeviceBootloader.hpp.

◆ watchdogThread

std::thread dai::DeviceBootloader::watchdogThread
private

Definition at line 519 of file DeviceBootloader.hpp.


The documentation for this class was generated from the following files:


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