~aleteoryx/muditaos

14f78ffc0757589530c7cf95132e0b40246ed2f1 — Mateusz Piesta 3 years ago 60c7810
[BH-1552] Harmony crashes during startup

Fixed crashing device.
Bell temperature sensor refactor.
14 files changed, 260 insertions(+), 290 deletions(-)

M module-bsp/CMakeLists.txt
M module-bsp/board/linux/CMakeLists.txt
D module-bsp/board/linux/bell_temp_sensor/bell_temp_sensor.cpp
M module-bsp/board/rt1051/bellpx/CMakeLists.txt
D module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/CT7117.hpp
D module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/bell_temp_sensor.cpp
M module-bsp/board/rt1051/bellpx/hal/battery_charger/BatteryCharger.cpp
M module-bsp/board/rt1051/bellpx/hal/temperature_source/TemperatureSource.cpp
D module-bsp/bsp/bell_temp_sensor/bell_temp_sensor.hpp
M module-bsp/devices/power/CW2015.cpp
A module-bsp/devices/temperature/CT7117.cpp
A module-bsp/devices/temperature/CT7117.hpp
M module-bsp/drivers/i2c/DriverI2C.hpp
M module-utils/utility/Units.hpp
M module-bsp/CMakeLists.txt => module-bsp/CMakeLists.txt +1 -0
@@ 15,6 15,7 @@ target_sources(
        devices/Device.cpp
        devices/power/CW2015.cpp
        devices/power/MP2639B.cpp
        devices/temperature/CT7117.cpp
        drivers/dma/DriverDMA.cpp
        drivers/dmamux/DriverDMAMux.cpp
        drivers/gpio/DriverGPIO.cpp

M module-bsp/board/linux/CMakeLists.txt => module-bsp/board/linux/CMakeLists.txt +0 -1
@@ 27,7 27,6 @@ target_sources(module-bsp
                hal/temperature_source/TemperatureSource.cpp
                hal/battery_charger/BatteryCharger.cpp
                hal/key_input/KeyInput.cpp
                bell_temp_sensor/bell_temp_sensor.cpp

                ${CMAKE_CURRENT_BINARY_DIR}/eink-config.h
)

D module-bsp/board/linux/bell_temp_sensor/bell_temp_sensor.cpp => module-bsp/board/linux/bell_temp_sensor/bell_temp_sensor.cpp +0 -46
@@ 1,46 0,0 @@
// Copyright (c) 2017-2021, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "bsp/bell_temp_sensor/bell_temp_sensor.hpp"
#include <log/log.hpp>

namespace bsp::bell_temp_sensor
{
    bool isFahrenheit                          = false;
    constexpr auto celsius_temperature_mock    = 21.0;
    constexpr auto fahrenheit_temperature_mock = (celsius_temperature_mock * 1.8) + 32;

    std::int32_t init(bool Fahrenheit)
    {
        isFahrenheit = Fahrenheit;

        return 0;
    }

    void deinit()
    {}

    bool standby()
    {
        return true;
    }

    bool wakeup()
    {
        return true;
    }

    Temperature readout()
    {
        if (isFahrenheit)
            return fahrenheit_temperature_mock;
        else
            return celsius_temperature_mock;
    }

    bool isPresent()
    {
        return true;
    }

} // namespace bsp::bell_temp_sensor

M module-bsp/board/rt1051/bellpx/CMakeLists.txt => module-bsp/board/rt1051/bellpx/CMakeLists.txt +0 -1
@@ 17,7 17,6 @@ target_sources(
        bsp/audio/AW8898driver.cpp
        bsp/audio/CodecAW8898.cpp

        bsp/bell_temp_sensor/bell_temp_sensor.cpp
        bsp/eink/eink_pin_config.cpp
        bsp/lpm/PowerProfile.cpp
        bsp/lpm/RT1051LPM.cpp

D module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/CT7117.hpp => module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/CT7117.hpp +0 -39
@@ 1,39 0,0 @@
// Copyright (c) 2017-2021, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#pragma once

#include <cstdint>

namespace bsp::bell_temp_sensor
{
    constexpr inline auto CT7117_DEVICE_ADDR = (0x90 >> 1);
    constexpr inline auto CT7117_DEVICE_ID   = 0x59;

    enum class CT7117_Registers
    {
        Temp          = 0x00,
        Config        = 0x01,
        Low_Temp_Set  = 0x02,
        High_Temp_Set = 0x03,
        ID            = 0x07
    };

    enum class CT7117_Config_Reg
    {
        OTS  = (1 << 15),
        F1   = (1 << 12),
        F0   = (1 << 11),
        ALTM = (1 << 9),
        SD   = (1 << 8),
        EM   = (1 << 7),
        RES1 = (1 << 6),
        RES0 = (1 << 5),
        TO   = (1 << 4),
        PEC  = (1 << 3),
        CR1  = (1 << 2),
        CR0  = (1 << 1),
        OS   = (1 << 0)
    };

} // namespace bsp::bell_temp_sensor

D module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/bell_temp_sensor.cpp => module-bsp/board/rt1051/bellpx/bsp/bell_temp_sensor/bell_temp_sensor.cpp +0 -144
@@ 1,144 0,0 @@
// Copyright (c) 2017-2021, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "bsp/bell_temp_sensor/bell_temp_sensor.hpp"
#include "CT7117.hpp"
#include <board/BoardDefinitions.hpp>
#include <drivers/i2c/DriverI2C.hpp>
#include <drivers/gpio/DriverGPIO.hpp>

#include "fsl_common.h"
#include <log/log.hpp>

namespace bsp::bell_temp_sensor
{
    using namespace drivers;

    bool isFahrenheit = false;

    namespace
    {
        std::shared_ptr<drivers::DriverI2C> i2c;
        bool isInitiated = false;

        drivers::I2CAddress addr = {
            .deviceAddress = static_cast<uint32_t>(CT7117_DEVICE_ADDR), .subAddress = 0, .subAddressSize = 1};

        bool writeSingleRegister(std::uint32_t address, std::uint16_t *to_send)
        {
            addr.subAddress          = address;
            const auto write_success = i2c->Write(addr, reinterpret_cast<uint8_t *>(to_send), 2);

            return write_success == 1;
        }

        ssize_t readSingleRegister(std::uint32_t address, std::uint16_t *readout)
        {
            addr.subAddress = address;
            return i2c->Read(addr, reinterpret_cast<uint8_t *>(readout), 2);
        }

        ssize_t readMeasurementRegisters(std::uint16_t *readout)
        {
            addr.subAddress = static_cast<std::uint32_t>(CT7117_Registers::Temp);
            return i2c->Read(addr, reinterpret_cast<uint8_t *>(readout), 2);
        }

        auto gpio_pwren = DriverGPIO::Create(static_cast<GPIOInstances>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_GPIO),
                                             DriverGPIOParams{});

    } // namespace

    std::int32_t init(bool Fahrenheit)
    {
        isFahrenheit = Fahrenheit;

        LOG_DEBUG("Initializing Bell temperature sensor");

        gpio_pwren->ConfPin(
            DriverGPIOPinParams{.dir      = DriverGPIOPinParams::Direction::Output,
                                .irqMode  = DriverGPIOPinParams::InterruptMode::NoIntmode,
                                .defLogic = 1,
                                .pin      = static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN)});
        gpio_pwren->WritePin(static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN), 1); // enable power

        if (isInitiated) {
            return isPresent() ? kStatus_Success : kStatus_Fail;
        }

        drivers::DriverI2CParams i2cParams;
        i2cParams.baudrate = static_cast<std::uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_I2C_BAUDRATE);
        i2c = drivers::DriverI2C::Create(static_cast<drivers::I2CInstances>(BoardDefinitions::BELL_TEMP_SENSOR_I2C),
                                         i2cParams);

        wakeup();

        isInitiated = true;

        return isPresent() ? kStatus_Success : kStatus_Fail;
    }

    void deinit()
    {
        standby();

        gpio_pwren->WritePin(static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN), 0); // disable power
    }

    bool standby()
    {
        uint16_t reg = 0;
        readSingleRegister(static_cast<uint32_t>(CT7117_Registers::Config), &reg);
        reg |= static_cast<uint16_t>(CT7117_Config_Reg::SD);
        return writeSingleRegister(static_cast<std::uint32_t>(CT7117_Registers::Config), &reg);
    }

    bool wakeup()
    {
        uint16_t reg = 0;
        readSingleRegister(static_cast<uint32_t>(CT7117_Registers::Config), &reg);
        reg &= ~(static_cast<uint16_t>(CT7117_Config_Reg::SD));
        return writeSingleRegister(static_cast<std::uint32_t>(CT7117_Registers::Config), &reg);
    }

    Temperature readout()
    {
        uint8_t reg[2] = {0, 0};
        float temp     = 0.0;

        readSingleRegister(static_cast<uint32_t>(CT7117_Registers::Temp), reinterpret_cast<uint16_t *>(&reg[0]));
        uint16_t reg16 =
            (static_cast<uint16_t>(reg[0]) << 8) | (static_cast<uint16_t>(reg[1]) & 0xFFE0); // 0.25 C resolution

        uint16_t integer    = 0;
        uint16_t fractional = 0;

        if (reg16 & 0x8000) {                                                 // sign bit present
            integer    = static_cast<uint16_t>(((~reg16 + 1) & 0x7FFF) >> 7); // remove sign bit and shift to lower byte
            fractional = static_cast<uint16_t>(((~reg16 + 1) & 0x7F) * 0.78125);
            temp       = -1 * (static_cast<float>(integer) + (static_cast<float>(fractional) / 100.0));
        }
        else {
            integer    = static_cast<uint16_t>((reg16 & 0x7FFF) >> 7); // remove sign bit and shift to lower byte
            fractional = static_cast<uint16_t>((reg16 & 0x7F) * 0.78125);
            temp       = static_cast<float>(integer) + (static_cast<float>(fractional) / 100.0);
        }

        if (isFahrenheit)
            temp = (temp * 1.8) + 32.00;

        return temp;
    }

    bool isPresent()
    {
        std::uint8_t readout;
        addr.subAddress = static_cast<uint8_t>(CT7117_Registers::ID);
        i2c->Read(addr, reinterpret_cast<uint8_t *>(&readout), 1);

        LOG_DEBUG("Bell temperature sensor %s", (readout == CT7117_DEVICE_ID) ? "present" : "error !");

        return readout == CT7117_DEVICE_ID;
    }

} // namespace bsp::bell_temp_sensor

M module-bsp/board/rt1051/bellpx/hal/battery_charger/BatteryCharger.cpp => module-bsp/board/rt1051/bellpx/hal/battery_charger/BatteryCharger.cpp +4 -3
@@ 71,6 71,7 @@ namespace hal::battery
        xQueueHandle notification_channel;
        inline static std::unique_ptr<BatteryWorkerQueue> worker_queue;

        std::shared_ptr<drivers::DriverI2C> i2c;
        std::shared_ptr<drivers::DriverGPIO> charger_gpio_chgok;
        std::shared_ptr<drivers::DriverGPIO> charger_gpio;
        mutable bsp::devices::power::MP2639B charger;


@@ 80,8 81,8 @@ namespace hal::battery
    };

    BellBatteryCharger::BellBatteryCharger(xQueueHandle irqQueueHandle)
        : notification_channel{irqQueueHandle}, charger_gpio_chgok{drivers::DriverGPIO::Create(charger_irq_gpio_chgok,
                                                                                               {})},
        : notification_channel{irqQueueHandle}, i2c{drivers::DriverI2C::Create(i2c_instance, i2c_params)},
          charger_gpio_chgok{drivers::DriverGPIO::Create(charger_irq_gpio_chgok, {})},
          charger_gpio{drivers::DriverGPIO::Create(charger_irq_gpio, {})}, charger{MP2639B::Configuration{
                                                                               charger_gpio,
                                                                               charger_irq_pin_mode,


@@ 103,7 104,7 @@ namespace hal::battery
                                                                               }}},

          fuel_gauge_gpio{drivers::DriverGPIO::Create(fuel_gauge_irq_gpio_instance, {})},
          fuel_gauge{CW2015{*drivers::DriverI2C::Create(i2c_instance, i2c_params), battery_shutdown_threshold}}
          fuel_gauge{CW2015{*i2c, battery_shutdown_threshold}}
    {

        reinit_timer = xTimerCreate("reinit_timer", reinit_poll_time, pdFALSE, this, [](TimerHandle_t xTimer) {

M module-bsp/board/rt1051/bellpx/hal/temperature_source/TemperatureSource.cpp => module-bsp/board/rt1051/bellpx/hal/temperature_source/TemperatureSource.cpp +52 -10
@@ 1,27 1,69 @@
// Copyright (c) 2017-2021, Mudita Sp. z.o.o. All rights reserved.
// Copyright (c) 2017-2022, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include <hal/temperature_source/TemperatureSource.hpp>
#include <hal/GenericFactory.hpp>
#include "bsp/bell_temp_sensor/bell_temp_sensor.hpp"
#include "hal/temperature_source/TemperatureSource.hpp"
#include "hal/GenericFactory.hpp"
#include "devices/temperature/CT7117.hpp"
#include "drivers/gpio/DriverGPIO.hpp"
#include "board/BoardDefinitions.hpp"

#include <stdexcept>

namespace hal::temperature
{
    class BellTemperatureSource : public AbstractTemperatureSource
    using namespace drivers;

    class PowerEnable
    {
      public:
        BellTemperatureSource()
        PowerEnable()
        {
            power_pin = DriverGPIO::Create(static_cast<GPIOInstances>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_GPIO),
                                           DriverGPIOParams{});

            power_pin->ConfPin(
                DriverGPIOPinParams{.dir      = DriverGPIOPinParams::Direction::Output,
                                    .irqMode  = DriverGPIOPinParams::InterruptMode::NoIntmode,
                                    .defLogic = 1,
                                    .pin      = static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN)});

            power_pin->WritePin(static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN), 1);
        }
        ~PowerEnable()
        {
            bsp::bell_temp_sensor::init();
            power_pin->WritePin(static_cast<uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_PWR_PIN), 0);
        }
        ~BellTemperatureSource()

      private:
        std::shared_ptr<drivers::DriverGPIO> power_pin;
    };

    class BellTemperatureSource : public AbstractTemperatureSource
    {
      public:
        BellTemperatureSource()
            : i2c{drivers::DriverI2C::Create(
                  static_cast<drivers::I2CInstances>(BoardDefinitions::BELL_TEMP_SENSOR_I2C),
                  {static_cast<std::uint32_t>(BoardDefinitions::BELL_TEMP_SENSOR_I2C_BAUDRATE)})},
              ct7117{ct7117_id, *i2c}
        {
            bsp::bell_temp_sensor::deinit();
            if (not ct7117.poll()) {
                throw std::runtime_error("CT7117 chip not present");
            }
            if (not ct7117.wakeup()) {
                throw std::runtime_error("Waking up CT7117 failed");
            }
        }
        Result read()
        {
            return bsp::bell_temp_sensor::readout();
            return ct7117.get_temperature();
        }

      private:
        static constexpr auto ct7117_id = (0x90 >> 1);
        PowerEnable power_enable;
        std::shared_ptr<drivers::DriverI2C> i2c;
        bsp::devices::temperature::CT7117::CT7117 ct7117;
    };

    std::shared_ptr<AbstractTemperatureSource> AbstractTemperatureSource::Factory::create()

D module-bsp/bsp/bell_temp_sensor/bell_temp_sensor.hpp => module-bsp/bsp/bell_temp_sensor/bell_temp_sensor.hpp +0 -31
@@ 1,31 0,0 @@
// Copyright (c) 2017-2020, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#pragma once

#include <cstdint>

extern "C"
{
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
}

namespace bsp::bell_temp_sensor
{
    using Temperature = float;

    std::int32_t init(bool Fahrenheit = false);

    void deinit();

    bool standby();

    bool wakeup();

    bool isPresent();

    Temperature readout();

} // namespace bsp::bell_temp_sensor

M module-bsp/devices/power/CW2015.cpp => module-bsp/devices/power/CW2015.cpp +13 -12
@@ 277,18 277,19 @@ namespace bsp::devices::power
        BATTINFO profile{};
        RetCodes ret_code{RetCodes::Ok};

        std::all_of(profile.cbegin(), profile.cend(), [this, ret_code, reg = BATTINFO::ADDRESS](const auto &e) mutable {
            const auto result = read(reg++);
            if (not result) {
                ret_code = RetCodes::CommunicationError;
                return false;
            }
            if (*result != e) {
                ret_code = RetCodes::ProfileInvalid;
                return false;
            }
            return true;
        });
        std::all_of(
            profile.cbegin(), profile.cend(), [this, &ret_code, reg = BATTINFO::ADDRESS](const auto &e) mutable {
                const auto result = read(reg++);
                if (not result) {
                    ret_code = RetCodes::CommunicationError;
                    return false;
                }
                if (*result != e) {
                    ret_code = RetCodes::ProfileInvalid;
                    return false;
                }
                return true;
            });

        return ret_code;
    }

A module-bsp/devices/temperature/CT7117.cpp => module-bsp/devices/temperature/CT7117.cpp +150 -0
@@ 0,0 1,150 @@
// Copyright (c) 2017-2022, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "CT7117.hpp"

#include <array>

namespace
{
    enum class Registers
    {
        Temp          = 0x00,
        Config        = 0x01,
        Low_Temp_Set  = 0x02,
        High_Temp_Set = 0x03,
        ID            = 0x07
    };

    enum class ConfigReg
    {
        OTS  = (1 << 15),
        F1   = (1 << 12),
        F0   = (1 << 11),
        ALTM = (1 << 9),
        SD   = (1 << 8),
        EM   = (1 << 7),
        RES1 = (1 << 6),
        RES0 = (1 << 5),
        TO   = (1 << 4),
        PEC  = (1 << 3),
        CR1  = (1 << 2),
        CR0  = (1 << 1),
        OS   = (1 << 0)
    };

    using namespace bsp::devices::temperature::CT7117;

    std::array<std::uint8_t, 2U> to_bytes(const std::uint16_t value)
    {
        return {static_cast<std::uint8_t>(value & 0xFF00 >> 8U), static_cast<std::uint8_t>(value & 0xFF)};
    }

    std::uint16_t from_bytes(std::array<std::uint8_t, 2U> bytes)
    {
        return bytes[0] << 8U | bytes[1];
    }

    ssize_t write_register16(const std::uint8_t dev_id,
                             drivers::DriverI2C &i2c,
                             const Registers address,
                             const std::uint16_t reg)
    {
        const drivers::I2CAddress addr = {
            .deviceAddress = dev_id, .subAddress = static_cast<std::uint32_t>(address), .subAddressSize = 1};

        return i2c.Write(addr, &to_bytes(reg)[0], sizeof(reg));
    }

    std::optional<std::uint16_t> read_register16(const std::uint8_t dev_id,
                                                 drivers::DriverI2C &i2c,
                                                 const Registers address)
    {
        const drivers::I2CAddress addr = {
            .deviceAddress = dev_id, .subAddress = static_cast<std::uint32_t>(address), .subAddressSize = 1};
        std::array<std::uint8_t, 2U> ret_value{};

        if (const auto result = i2c.Read(addr, &ret_value[0], ret_value.size()); result == ret_value.size()) {
            return from_bytes(ret_value);
        }
        return std::nullopt;
    }

    units::Temperature from_raw(const std::uint16_t raw)
    {
        auto is_sign_present = [](const std::uint16_t raw) { return ((raw & 0x8000) != 0); };

        if (is_sign_present(raw)) {
            const auto integer =
                static_cast<std::uint16_t>(((~raw + 1) & 0x7FFF) >> 7); // remove sign bit and shift to lower byte
            const auto fractional = static_cast<std::uint16_t>(((~raw + 1) & 0x7F) * 0.78125);
            return -1 * (static_cast<float>(integer) + (static_cast<float>(fractional) / 100.0));
        }
        else {
            const auto integer =
                static_cast<std::uint16_t>((raw & 0x7FFF) >> 7); // remove sign bit and shift to lower byte
            const auto fractional = static_cast<std::uint16_t>((raw & 0x7F) * 0.78125);
            return static_cast<float>(integer) + (static_cast<float>(fractional) / 100.0);
        }
    }

    std::uint16_t adjust_resolution(const std::uint16_t value)
    {
        /// Resolution = 0.25°C
        return value & 0xFFE0;
    }
} // namespace

namespace bsp::devices::temperature::CT7117
{

    CT7117::CT7117(const std::uint8_t id, drivers::DriverI2C &i2c) : device_id{id}, i2c{i2c}
    {}

    CT7117::~CT7117()
    {
        standby();
    }

    bool CT7117::standby()
    {
        auto reg = read_register16(device_id, i2c, Registers::Config);
        if (not reg) {
            return false;
        }
        *reg |= static_cast<std::uint16_t>(ConfigReg::SD);
        return write_register16(device_id, i2c, Registers::Config, *reg) == sizeof(*reg);
    }

    bool CT7117::wakeup()
    {
        auto reg = read_register16(device_id, i2c, Registers::Config);
        if (not reg) {
            return false;
        }
        *reg &= ~(static_cast<std::uint16_t>(ConfigReg::SD));
        return write_register16(device_id, i2c, Registers::Config, *reg) == sizeof(*reg);
    }

    std::optional<units::Temperature> CT7117::get_temperature() const
    {
        auto reg = read_register16(device_id, i2c, Registers::Temp);
        if (not reg) {
            return std::nullopt;
        }

        return from_raw(adjust_resolution(*reg));
    }

    bool CT7117::poll() const
    {
        constexpr auto DEVICE_ID      = 0x59;
        const drivers::I2CAddress reg = {
            .deviceAddress = device_id, .subAddress = static_cast<std::uint32_t>(Registers::ID), .subAddressSize = 1};

        std::uint8_t id{};
        const auto id_size = sizeof id;

        return i2c.Read(reg, &id, id_size) == id_size and id == DEVICE_ID;
    }
} // namespace bsp::devices::temperature::CT7117

A module-bsp/devices/temperature/CT7117.hpp => module-bsp/devices/temperature/CT7117.hpp +37 -0
@@ 0,0 1,37 @@
// Copyright (c) 2017-2022, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#pragma once

#include "drivers/i2c/DriverI2C.hpp"
#include <Units.hpp>

#include <optional>

namespace bsp::devices::temperature::CT7117
{
    class CT7117
    {
      public:
        CT7117(std::uint8_t id, drivers::DriverI2C &i2c);
        ~CT7117();
        CT7117(const CT7117 &)     = delete;
        CT7117(CT7117 &&) noexcept = default;
        CT7117 &operator=(const CT7117 &) = delete;
        CT7117 &operator=(CT7117 &&) noexcept = delete;

        /// Check if the chip is available, i.e is present on the I2C bus
        bool poll() const;
        /// Put the chip into low-power state
        bool standby();
        /// Put the chip into normal/operational mode
        bool wakeup();
        /// Return the current temperature in °C
        std::optional<units::Temperature> get_temperature() const;

      private:
        std::uint8_t device_id;
        drivers::DriverI2C &i2c;
    };

} // namespace bsp::devices::temperature::CT7117

M module-bsp/drivers/i2c/DriverI2C.hpp => module-bsp/drivers/i2c/DriverI2C.hpp +0 -1
@@ 37,7 37,6 @@ namespace drivers
    struct DriverI2CParams
    {
        uint32_t baudrate;
        // TODO:M.P add slave conf
    };

    struct I2CAddress

M module-utils/utility/Units.hpp => module-utils/utility/Units.hpp +3 -2
@@ 7,6 7,7 @@

namespace units
{
    using Voltage = std::uint32_t; /// mV
    using SOC     = std::uint8_t;  /// 0-100%
    using Voltage     = std::uint32_t; /// mV
    using SOC         = std::uint8_t;  /// 0-100%
    using Temperature = float;
} // namespace units