Program Listing for File XLinkConnection.hpp

Return to documentation for file (include/depthai/xlink/XLinkConnection.hpp)

#pragma once

// Std
#include <atomic>
#include <chrono>
#include <cstdint>
#include <filesystem>
#include <list>
#include <mutex>
#include <string>
#include <thread>
#include <tuple>
#include <unordered_map>
#include <vector>

// project
#include "depthai/utility/ProfilingData.hpp"

// Libraries
#include <XLink/XLinkPublicDefines.h>

namespace dai {

struct DeviceInfo {
    DeviceInfo() = default;
    DeviceInfo(std::string name, std::string deviceId, XLinkDeviceState_t state, XLinkProtocol_t protocol, XLinkPlatform_t platform, XLinkError_t status);
    explicit DeviceInfo(std::string deviceIdOrName);
    explicit DeviceInfo(const deviceDesc_t& desc);
    deviceDesc_t getXLinkDeviceDesc() const;
    [[deprecated("Use getDeviceId() instead")]] std::string getMxId() const;
    std::string getDeviceId() const;
    std::string toString() const;

    std::string name = "";
    std::string deviceId = "";
    XLinkDeviceState_t state = X_LINK_ANY_STATE;
    XLinkProtocol_t protocol = X_LINK_ANY_PROTOCOL;
    XLinkPlatform_t platform = X_LINK_ANY_PLATFORM;
    XLinkError_t status = X_LINK_SUCCESS;
};

class XLinkConnection {
   public:
    // static API

    static std::vector<DeviceInfo> getAllConnectedDevices(XLinkDeviceState_t state = X_LINK_ANY_STATE,
                                                          bool skipInvalidDevices = true,
                                                          int timeoutMs = XLINK_DEVICE_DEFAULT_SEARCH_TIMEOUT_MS);

    static std::tuple<bool, DeviceInfo> getFirstDevice(XLinkDeviceState_t state = X_LINK_ANY_STATE, bool skipInvalidDevices = true);

    static std::tuple<bool, DeviceInfo> getDeviceById(std::string deviceId, XLinkDeviceState_t state = X_LINK_ANY_STATE, bool skipInvalidDevice = true);

    static DeviceInfo bootBootloader(const DeviceInfo& devInfo);

    static ProfilingData getGlobalProfilingData();

    XLinkConnection(const DeviceInfo& deviceDesc, std::vector<std::uint8_t> mvcmdBinary, XLinkDeviceState_t expectedState = X_LINK_BOOTED);
    XLinkConnection(const DeviceInfo& deviceDesc, std::filesystem::path pathToMvcmd, XLinkDeviceState_t expectedState = X_LINK_BOOTED);
    explicit XLinkConnection(const DeviceInfo& deviceDesc, XLinkDeviceState_t expectedState = X_LINK_BOOTED);

    ~XLinkConnection();

    void setRebootOnDestruction(bool reboot);
    bool getRebootOnDestruction() const;

    int getLinkId() const;

    void close();

    bool isClosed() const;

    ProfilingData getProfilingData();

   private:
    friend struct XLinkReadError;
    friend struct XLinkWriteError;
    // static
    static bool bootAvailableDevice(const deviceDesc_t& deviceToBoot, const std::filesystem::path& pathToMvcmd);
    static bool bootAvailableDevice(const deviceDesc_t& deviceToBoot, std::vector<std::uint8_t>& mvcmd);
    static std::string convertErrorCodeToString(XLinkError_t errorCode);

    void initDevice(const DeviceInfo& deviceToInit, XLinkDeviceState_t expectedState = X_LINK_BOOTED);

    bool bootDevice = true;
    bool bootWithPath = true;
    std::filesystem::path pathToMvcmd;
    std::vector<std::uint8_t> mvcmd;

    bool rebootOnDestruction{true};

    int deviceLinkId = -1;

    DeviceInfo deviceInfo;

    // closed
    mutable std::mutex closedMtx;
    bool closed{false};

    constexpr static std::chrono::milliseconds WAIT_FOR_BOOTUP_TIMEOUT{15000};
    constexpr static std::chrono::milliseconds WAIT_FOR_CONNECT_TIMEOUT{5000};
    constexpr static std::chrono::milliseconds POLLING_DELAY_TIME{10};
};

}  // namespace dai