Program Listing for File DeviceBootloader.hpp
↰ Return to documentation for file (include/depthai/device/DeviceBootloader.hpp)
// IWYU pragma: private, include "depthai/depthai.hpp"
#pragma once
// std
#include <string>
#include <thread>
#include <type_traits>
// project
#include "CallbackHandler.hpp"
#include "depthai/common/UsbSpeed.hpp"
#include "depthai/pipeline/Pipeline.hpp"
#include "depthai/xlink/XLinkConnection.hpp"
#include "depthai/xlink/XLinkStream.hpp"
// shared
#include "depthai-bootloader-shared/Config.hpp"
#include "depthai-bootloader-shared/Memory.hpp"
#include "depthai-bootloader-shared/Section.hpp"
#include "depthai-bootloader-shared/Type.hpp"
namespace dai {
namespace fs = std::filesystem;
// DeviceBootloader (RAII), connects to device and maintains watchdog ...
class DeviceBootloader {
public:
// Alias
using Type = dai::bootloader::Type;
using Memory = dai::bootloader::Memory;
using Section = dai::bootloader::Section;
using UsbConfig = dai::bootloader::UsbConfig;
using NetworkConfig = dai::bootloader::NetworkConfig;
// Derive and extend bootloader::Config for easier usage
struct Config : public bootloader::Config {
void setStaticIPv4(std::string ip, std::string mask, std::string gateway);
void setDynamicIPv4(std::string ip, std::string mask, std::string gateway);
bool isStaticIPV4();
std::string getIPv4();
std::string getIPv4Mask();
std::string getIPv4Gateway();
void setDnsIPv4(std::string dns, std::string dnsAlt = "");
std::string getDnsIPv4();
std::string getDnsAltIPv4();
void setUsbTimeout(std::chrono::milliseconds ms);
std::chrono::milliseconds getUsbTimeout();
void setNetworkTimeout(std::chrono::milliseconds ms);
std::chrono::milliseconds getNetworkTimeout();
void setMacAddress(std::string mac);
std::string getMacAddress();
void setUsbMaxSpeed(UsbSpeed speed);
UsbSpeed getUsbMaxSpeed();
nlohmann::json toJson() const;
static Config fromJson(nlohmann::json);
private:
nlohmann::json data;
};
// Add an alias to Version
using Version = dai::Version;
struct ApplicationInfo {
Memory memory;
bool hasApplication;
std::string firmwareVersion;
std::string applicationName;
};
struct MemoryInfo {
bool available;
std::int64_t size;
std::string info;
};
// constants
static constexpr const Type DEFAULT_TYPE{Type::USB};
// Static API
static std::tuple<bool, DeviceInfo> getFirstAvailableDevice();
static std::vector<DeviceInfo> getAllAvailableDevices();
static std::vector<uint8_t> createDepthaiApplicationPackage(
const Pipeline& pipeline, const fs::path& pathToCmd = {}, bool compress = false, std::string applicationName = "", bool checkChecksum = false);
static std::vector<uint8_t> createDepthaiApplicationPackage(const Pipeline& pipeline,
bool compress,
std::string applicationName = "",
bool checkChecksum = false);
static void saveDepthaiApplicationPackage(const fs::path& path,
const Pipeline& pipeline,
const fs::path& pathToCmd = {},
bool compress = false,
std::string applicationName = "",
bool checkChecksum = false);
static void saveDepthaiApplicationPackage(
const fs::path& path, const Pipeline& pipeline, bool compress, std::string applicationName = "", bool checkChecksum = false);
static Version getEmbeddedBootloaderVersion();
static std::vector<std::uint8_t> getEmbeddedBootloaderBinary(Type type = DEFAULT_TYPE);
DeviceBootloader() = delete;
explicit DeviceBootloader(const DeviceInfo& devInfo);
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(const DeviceInfo& devInfo, const fs::path& pathToBootloader, bool allowFlashingBootloader = false);
DeviceBootloader(std::string nameOrDeviceId, bool allowFlashingBootloader = false);
~DeviceBootloader();
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> flash(
const Pipeline& pipeline, bool compress = false, std::string applicationName = "", Memory memory = Memory::AUTO, bool checkChecksum = false);
ApplicationInfo readApplicationInfo(Memory memory);
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> flashClear(Memory memory = Memory::AUTO);
std::tuple<bool, std::string> flashBootloader(std::function<void(float)> progressCallback, const fs::path& path = {});
std::tuple<bool, std::string> flashBootloader(Memory memory, Type type, std::function<void(float)> progressCallback, const fs::path& path = {});
std::tuple<bool, std::string> flashUserBootloader(std::function<void(float)> progressCallback, const fs::path& path = {});
std::tuple<bool, std::string> flashGpioModeBootHeader(Memory memory, int gpioMode);
std::tuple<bool, std::string> flashUsbRecoveryBootHeader(Memory memory);
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> flashFastBootHeader(
Memory memory, int32_t frequency = -1, int64_t location = -1, int32_t dummyCycles = -1, int64_t offset = -1);
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> 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);
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, std::vector<uint8_t>> readCustom(Memory memory, size_t offset, size_t size, std::function<void(float)> progressCb = nullptr);
nlohmann::json readConfigData(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 fs::path& configPath, Memory memory = Memory::AUTO, Type type = Type::AUTO);
std::tuple<bool, std::string> flashConfigClear(Memory memory = Memory::AUTO, Type type = Type::AUTO);
Config readConfig(Memory memory = Memory::AUTO, Type type = Type::AUTO);
std::tuple<bool, std::string> flashConfig(const Config& config, Memory memory = Memory::AUTO, Type type = Type::AUTO);
MemoryInfo getMemoryInfo(Memory memory);
bool isUserBootloaderSupported();
bool isUserBootloader();
void bootMemory(const std::vector<uint8_t>& fw);
void bootUsbRomBootloader();
Version getVersion() const;
bool isEmbeddedVersion() const;
Type getType() const;
bool isAllowedFlashingBootloader() const;
void close();
bool isClosed() const;
private:
// private static
// private methods
void init(bool embeddedMvcmd, const fs::path& pathToMvcmd, std::optional<bootloader::Type> type, bool allowBlFlash);
template <typename T>
bool sendRequest(const T& request);
template <typename T>
void sendRequestThrow(const T& request);
bool receiveResponseData(std::vector<uint8_t>& data);
template <typename T>
bool parseResponse(const std::vector<uint8_t>& data, T& response);
template <typename T>
bool receiveResponse(T& response);
template <typename T>
void receiveResponseThrow(T& response);
Version requestVersion();
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);
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);
void createWatchdog();
void destroyWatchdog();
// private variables
std::shared_ptr<XLinkConnection> connection;
DeviceInfo deviceInfo = {};
bool isEmbedded = false;
Type bootloaderType;
// closed
std::atomic<bool> closed{false};
// Watchdog thread
std::thread watchdogThread;
std::atomic<bool> watchdogRunning{true};
// Monitor thread
std::thread monitorThread;
std::mutex lastWatchdogPingTimeMtx;
std::chrono::steady_clock::time_point lastWatchdogPingTime;
// bootloader stream
std::unique_ptr<XLinkStream> stream;
// Allow flashing bootloader flag
bool allowFlashingBootloader = false;
// Current connected bootloader version
Version version{0, 0, 2};
};
} // namespace dai
// Global namespace
inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::Type& type) {
switch(type) {
case dai::DeviceBootloader::Type::AUTO:
out << "AUTO";
break;
case dai::DeviceBootloader::Type::USB:
out << "USB";
break;
case dai::DeviceBootloader::Type::NETWORK:
out << "NETWORK";
break;
}
return out;
}
inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::Memory& memory) {
switch(memory) {
case dai::DeviceBootloader::Memory::AUTO:
out << "AUTO";
break;
case dai::DeviceBootloader::Memory::FLASH:
out << "FLASH";
break;
case dai::DeviceBootloader::Memory::EMMC:
out << "EMMC";
break;
}
return out;
}
inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::Section& type) {
switch(type) {
case dai::DeviceBootloader::Section::AUTO:
out << "AUTO";
break;
case dai::DeviceBootloader::Section::HEADER:
out << "HEADER";
break;
case dai::DeviceBootloader::Section::BOOTLOADER:
out << "BOOTLOADER";
break;
case dai::DeviceBootloader::Section::USER_BOOTLOADER:
out << "USER_BOOTLOADER";
break;
case dai::DeviceBootloader::Section::BOOTLOADER_CONFIG:
out << "BOOTLOADER_CONFIG";
break;
case dai::DeviceBootloader::Section::APPLICATION:
out << "APPLICATION";
break;
}
return out;
}
inline std::ostream& operator<<(std::ostream& out, const dai::DeviceBootloader::Version& v) {
return out << v.toString();
}