Program Listing for File BoardConfig.hpp

Return to documentation for file (include/depthai/device/BoardConfig.hpp)

#pragma once

// std
#include <cstdint>
#include <unordered_map>

// project
#include "depthai/common/CameraBoardSocket.hpp"
#include "depthai/common/CameraImageOrientation.hpp"
#include "depthai/common/CameraSensorType.hpp"
#include "depthai/common/Extrinsics.hpp"
#include "depthai/common/UsbSpeed.hpp"
#include "depthai/common/optional.hpp"
#include "depthai/log/LogLevel.hpp"
#include "depthai/pipeline/datatype/ImgFrame.hpp"
#include "depthai/utility/Serialization.hpp"
#include "depthai/xlink/XLinkConstants.hpp"

namespace dai {

constexpr static uint32_t BOARD_CONFIG_MAGIC1 = 0x78010000U;
constexpr static uint32_t BOARD_CONFIG_MAGIC2 = 0x21ea17e6U;

struct BoardConfig {
    struct USB {
        uint16_t vid = 0x03e7, pid = 0xf63b;
        uint16_t flashBootedVid = 0x03e7, flashBootedPid = 0xf63d;
        UsbSpeed maxSpeed = UsbSpeed::SUPER;
        std::string productName, manufacturer;
    };

    USB usb;

    struct Network {
        uint16_t mtu = 0;
        bool xlinkTcpNoDelay = true;
    };

    Network network;

    std::vector<std::string> sysctl;

    std::optional<uint32_t> watchdogTimeoutMs;
    std::optional<uint32_t> watchdogInitialDelayMs;

    struct GPIO {
        enum Mode : std::int8_t { ALT_MODE_0 = 0, ALT_MODE_1, ALT_MODE_2, ALT_MODE_3, ALT_MODE_4, ALT_MODE_5, ALT_MODE_6, DIRECT };
        Mode mode = Mode::DIRECT;
        enum Direction : std::int8_t { INPUT = 0, OUTPUT = 1 };
        Direction direction = Direction::INPUT;
        enum Level : std::int8_t { LOW = 0, HIGH = 1 };
        Level level = Level::LOW;
        enum Pull : std::int8_t { NO_PULL = 0, PULL_UP = 1, PULL_DOWN = 2, BUS_KEEPER = 3 };
        Pull pull = Pull::NO_PULL;
        enum Drive : std::int8_t { MA_2 = 2, MA_4 = 4, MA_8 = 8, MA_12 = 12 };
        Drive drive = MA_2;
        bool schmitt = false, slewFast = false;
        GPIO() = default;
        GPIO(Direction direction) : direction(direction) {}
        GPIO(Direction direction, Level level) : direction(direction), level(level) {}
        GPIO(Direction direction, Level level, Pull pull) : direction(direction), level(level), pull(pull) {}
        GPIO(Direction direction, Mode mode) : mode(mode), direction(direction) {}
        GPIO(Direction direction, Mode mode, Pull pull) : mode(mode), direction(direction), pull(pull) {}
    };
    std::unordered_map<std::int8_t, GPIO> gpio;

    // Uart config

    struct UART {
        // TBD
        // std::int8_t tx, rx;
        std::int8_t tmp;
    };
    std::unordered_map<std::int8_t, UART> uart;

    std::optional<bool> pcieInternalClock;

    std::optional<bool> usb3PhyInternalClock;

    std::optional<bool> mipi4LaneRgb;

    std::optional<bool> emmc;

    std::optional<std::string> logPath;

    std::optional<size_t> logSizeMax;

    std::optional<LogLevel> logVerbosity;

    std::optional<bool> logDevicePrints;

    bool nonExclusiveMode = false;

    // TODO(themarpe) - add later when applicable
    // // Socket description
    // struct Socket {
    //     int i2cBus;
    //     int mipiStart, mipiEnd;  // inclusive
    //     int gpioPwr, gpioRst;
    //     float voltageCore, voltageAnalog, voltageInterface;
    //     // TODO(themarpe) - tbd if better placed here
    //     // std::optional<CameraBoardSocket> syncTo;
    // };
    // std::unordered_map<CameraBoardSocket, Socket> socket;

    struct Camera {
        std::string name;
        // TODO(themarpe) - add later when applicable
        // std::vector<std::string> sensorName;
        std::optional<CameraSensorType> sensorType = std::nullopt;
        // std::vector<vector> vcm;
        // std::optional<CameraBoardSocket> syncTo;
        std::optional<CameraImageOrientation> orientation = std::nullopt;
    };
    std::unordered_map<CameraBoardSocket, Camera> camera;

    struct IMU {
        IMU() : bus(0), interrupt(53), wake(34), csGpio(8), boot(46), reset(45) {}
        int8_t bus, interrupt, wake, csGpio, boot, reset;
    };
    std::optional<IMU> imu;

    struct UVC {
        std::string cameraName;
        uint16_t width, height;
        ImgFrame::Type frameType;
        bool enable;
        UVC(uint16_t width, uint16_t height) : width(width), height(height), frameType(ImgFrame::Type::NV12), enable(true) {}
        UVC() : UVC(1920, 1080) {}
    };
    std::optional<UVC> uvc;
    std::unordered_map<std::string, Extrinsics> defaultImuExtr;
};

DEPTHAI_SERIALIZE_EXT(BoardConfig::USB, vid, pid, flashBootedVid, flashBootedPid, maxSpeed, productName, manufacturer);
DEPTHAI_SERIALIZE_EXT(BoardConfig::Network, mtu, xlinkTcpNoDelay);
DEPTHAI_SERIALIZE_EXT(BoardConfig::GPIO, mode, direction, level, pull, drive, schmitt, slewFast);
DEPTHAI_SERIALIZE_EXT(BoardConfig::UART, tmp);
DEPTHAI_SERIALIZE_EXT(BoardConfig::Camera, name, sensorType, orientation);
DEPTHAI_SERIALIZE_EXT(BoardConfig::IMU, bus, interrupt, wake, csGpio, boot, reset);
DEPTHAI_SERIALIZE_EXT(BoardConfig::UVC, cameraName, width, height, frameType, enable);
DEPTHAI_SERIALIZE_EXT(BoardConfig,
                      usb,
                      network,
                      sysctl,
                      watchdogTimeoutMs,
                      watchdogInitialDelayMs,
                      gpio,
                      uart,
                      pcieInternalClock,
                      usb3PhyInternalClock,
                      emmc,
                      logPath,
                      logSizeMax,
                      logVerbosity,
                      logDevicePrints,
                      nonExclusiveMode,
                      camera,
                      imu,
                      uvc,
                      defaultImuExtr);

}  // namespace dai