~aleteoryx/muditaos

aee4561d81795372183109c851a97f9602eb372d — Lefucjusz 1 year, 4 months ago b9a106b
[BH-2048] Major Eink driver refactor

* Cleaned up BSP layer of Eink driver.
* Removed changing TCON config with
different refresh modes, used one set
of values for all modes instead.
* Moved coordinates transformation
routines to separate file.
* Minor fixes in 2bpp transformation
routine.
* Cleanups in lots of various
places.
M module-bsp/board/rt1051/CMakeLists.txt => module-bsp/board/rt1051/CMakeLists.txt +4 -4
@@ 10,11 10,11 @@ target_sources(module-bsp
		bsp/cellular/rt1051_cellular.cpp
		bsp/eeprom/eeprom.cpp
		bsp/eink_frontlight/eink_frontlight.cpp
		bsp/eink/bsp_eink.cpp
        bsp/eink/BspEink.cpp
		bsp/eink/ED028TC1.cpp
		bsp/eink/EinkDisplay.cpp
		bsp/eink/eink_binarization_luts.c
		bsp/eink/eink_dimensions.cpp
		bsp/eink/EinkDimensions.cpp
		bsp/eink/EinkBufferTransformation.cpp
		bsp/eMMC/fsl_mmc.c
		bsp/eMMC/fsl_sdmmc_common.c
		bsp/eMMC/fsl_sdmmc_event.c


@@ 33,6 33,7 @@ target_sources(module-bsp
		bsp/lpm/LDO.cpp
		bsp/lpm/DCDC.cpp
		bsp/magnetometer/ALS31300.cpp
		bsp/magnetometer/magnetometer.cpp
		bsp/pit/pit.cpp
		bsp/trng/trng.cpp
		bsp/trng/RT1051Trng.cpp


@@ 57,7 58,6 @@ target_sources(module-bsp
		drivers/RT1051DriverPWM.cpp
		drivers/RT1051DriverSEMC.cpp
		drivers/RT1051DriverUSDHC.cpp
   		bsp/magnetometer/magnetometer.cpp
)

target_include_directories(module-bsp

M module-bsp/board/rt1051/bellpx/eink-config.h => module-bsp/board/rt1051/bellpx/eink-config.h +1 -0
@@ 2,5 2,6 @@
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#pragma once

#define BOARD_EINK_DISPLAY_RES_X 600
#define BOARD_EINK_DISPLAY_RES_Y 480

M module-bsp/board/rt1051/bellpx/irq_gpio.cpp => module-bsp/board/rt1051/bellpx/irq_gpio.cpp +18 -18
@@ 11,7 11,7 @@
#include <fsl_pmu.h>
#include <fsl_rtwdog.h>

#include "board/rt1051/bsp/eink/bsp_eink.h"
#include "board/rt1051/bsp/eink/BspEink.hpp"
#include <hal/key_input/KeyInput.hpp>
#include <hal/battery_charger/BatteryChargerIRQ.hpp>
#include "board/BoardDefinitions.hpp"


@@ 80,12 80,12 @@ namespace bsp
        void GPIO1_Combined_0_15_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO1);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO1);

            if (irq_mask & (1 << static_cast<uint32_t>(BoardDefinitions::BELL_BATTERY_CHARGER_CHGOK_PIN))) {
            if (irq_mask & (1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_BATTERY_CHARGER_CHGOK_PIN))) {
                xHigherPriorityTaskWoken |= hal::battery::charger_irq();
            }
            if (irq_mask & (1 << static_cast<uint32_t>(BoardDefinitions::BELL_FUELGAUGE_ALRT_PIN))) {
            if (irq_mask & (1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_FUELGAUGE_ALRT_PIN))) {
                xHigherPriorityTaskWoken |= hal::battery::fuel_gauge_irq();
            }



@@ 99,7 99,7 @@ namespace bsp
        void GPIO1_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO1);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO1);

            // Clear all IRQs
            GPIO_PortClearInterruptFlags(GPIO1, irq_mask);


@@ 111,7 111,7 @@ namespace bsp
        void GPIO2_Combined_0_15_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO2);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO2);

            // Clear all IRQs
            GPIO_PortClearInterruptFlags(GPIO2, irq_mask);


@@ 123,15 123,15 @@ namespace bsp
        void GPIO2_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO2);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO2);

            if (irq_mask & ((1 << static_cast<uint32_t>(BoardDefinitions::BELL_SWITCHES_RIGHT)) |
                            (1 << static_cast<uint32_t>(BoardDefinitions::BELL_SWITCHES_LEFT)) |
                            (1 << static_cast<uint32_t>(BoardDefinitions::BELL_SWITCHES_LATCH)))) {
            if (irq_mask & ((1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_SWITCHES_RIGHT)) |
                            (1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_SWITCHES_LEFT)) |
                            (1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_SWITCHES_LATCH)))) {
                xHigherPriorityTaskWoken |= hal::key_input::GPIO2SwitchesIRQHandler(irq_mask);
            }

            if (irq_mask & (1 << static_cast<uint32_t>(BoardDefinitions::BELL_BATTERY_CHARGER_ACOK_PIN))) {
            if (irq_mask & (1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_BATTERY_CHARGER_ACOK_PIN))) {
                xHigherPriorityTaskWoken |= hal::battery::charger_irq();
            }



@@ 145,10 145,10 @@ namespace bsp
        void GPIO3_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO3);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO3);

            if (irq_mask & (1 << BOARD_EINK_BUSY_GPIO_PIN)) {
                xHigherPriorityTaskWoken |= BSP_EinkBusyPinStateChangeHandler();
                xHigherPriorityTaskWoken |= bsp::eink::busyPinStateChangeHandler();
            }

            // Clear all IRQs on the GPIO3 port


@@ 160,10 160,10 @@ namespace bsp

        void GPIO5_Combined_0_15_IRQHandler(void)
        {
            uint32_t irq_mask = GPIO_GetPinsInterruptFlags(GPIO5);
            std::uint32_t irq_mask = GPIO_GetPinsInterruptFlags(GPIO5);

            BaseType_t xHigherPriorityTaskWoken = hal::key_input::GPIO5SwitchesIRQHandler(
                1 << static_cast<uint32_t>(BoardDefinitions::BELL_CENTER_SWITCH));
                1 << static_cast<std::uint32_t>(BoardDefinitions::BELL_CENTER_SWITCH));
            // Clear all IRQs on the GPIO5 port
            GPIO_PortClearInterruptFlags(GPIO5, irq_mask);



@@ 203,11 203,11 @@ namespace bsp
         * Get the value of last PC state and store in non-volatile SNVS register
         * to have any data that can be used to debug if program died in IRQ or
         * critical section and neither log nor crashdump was created. */
        __attribute__((used, noreturn)) void RTWDOG_Handler(const uint32_t *sp)
        __attribute__((used, noreturn)) void RTWDOG_Handler(const std::uint32_t *sp)
        {
            RTWDOG_ClearStatusFlags(RTWDOG, kRTWDOG_InterruptFlag);

            const uint32_t pc = sp[6];
            const std::uint32_t pc = sp[6];
            SNVS->LPGPR[1]    = pc;

            WDOG1->WCR &= ~WDOG_WCR_WDA_MASK;


@@ 230,7 230,7 @@ namespace bsp
        // Enable PMU brownout interrupt
        void ANATOP_EVENT0_IRQHandler(void)
        {
            const uint32_t status = PMU_GetStatusFlags(PMU);
            const std::uint32_t status = PMU_GetStatusFlags(PMU);

            /* If the PMU brownout detects too low voltage
             * immediately reset board's main DCDC converter

A module-bsp/board/rt1051/bsp/eink/BspEink.cpp => module-bsp/board/rt1051/bsp/eink/BspEink.cpp +478 -0
@@ 0,0 1,478 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "BspEink.hpp"

#include "board.h"
#include "fsl_lpspi.h"
#include "fsl_lpspi_edma.h"

#include "dma_config.h"
#include "bsp/eink/eink_gpio.hpp"

#include "FreeRTOS.h"
#include "semphr.h"

#include "drivers/dmamux/DriverDMAMux.hpp"
#include "drivers/dma/DriverDMA.hpp"
#include "drivers/gpio/DriverGPIO.hpp"
#include "board/BoardDefinitions.hpp"

namespace bsp::eink
{
    using namespace drivers;

    namespace
    {
        enum class BusyWaitEventState
        {
            Registered,
            NotRegistered
        };

        struct LpspiResource
        {
            LPSPI_Type *base;
            std::uint32_t instance;
            std::uint32_t (*GetFreq)();
        };

        struct LpspiEdmaResource
        {
            DMA_Type *txEdmaBase;
            std::uint32_t txEdmaChannel;
            std::uint8_t txDmaRequest;

            DMA_Type *rxEdmaBase;
            std::uint32_t rxEdmaChannel;
            std::uint8_t rxDmaRequest;

#if (defined(FSL_FEATURE_SOC_DMAMUX_COUNT) && FSL_FEATURE_SOC_DMAMUX_COUNT)
            DMAMUX_Type *txDmamuxBase;
            DMAMUX_Type *rxDmamuxBase;
#endif
        };

        struct BspEinkDriver
        {
            LpspiResource *resource;
            LpspiEdmaResource *dmaResource;
            lpspi_master_edma_handle_t *handle;
            edma_handle_t *edmaRxRegToRxDataHandle;
            edma_handle_t *edmaTxDataToTxRegHandle;
            std::uint32_t baudRate_Bps;
            std::uint8_t flags; // Control and state flags

            BusyEventCallback event;
            SPICSConfig csConfig;             // Current transfer chip select configuration (automatic of manual)
            BusyWaitEventState eventRegister; // Tells if something is waiting for not busy event
        };

        lpspi_master_config_t spi_config;
        std::shared_ptr<DriverGPIO> gpio;
        std::shared_ptr<DriverDMA> dma;
        std::shared_ptr<DriverDMAMux> dmamux;
        std::unique_ptr<DriverDMAHandle> rxDMAHandle;
        std::unique_ptr<DriverDMAHandle> txDMAHandle;

        constexpr auto transferWriteClockHz = 18'000'000;
        constexpr auto transferReadClockHz  = 3'000'000;
        constexpr auto delayInNanoSec       = 1'000'000'000 / transferWriteClockHz;
        const auto lpspiBase                = BOARD_EINK_LPSPI_BASE;

        std::uint32_t lpspiGetFreq()
        {
            return GetPerphSourceClock(PerphClock_LPSPI);
        }

        LpspiResource lpspiResource = {lpspiBase, 1, lpspiGetFreq};

        LpspiEdmaResource lpspiEdmaResource = {
            BSP_EINK_LPSPI_DMA_TX_DMA_BASE,
            BSP_EINK_LPSPI_DMA_TX_CH,
            BSP_EINK_LPSPI_DMA_TX_PERI_SEL,
            BSP_EINK_LPSPI_DMA_RX_DMA_BASE,
            BSP_EINK_LPSPI_DMA_RX_CH,
            BSP_EINK_LPSPI_DMA_RX_PERI_SEL,
            BSP_EINK_LPSPI_DMA_TX_DMAMUX_BASE,
            BSP_EINK_LPSPI_DMA_RX_DMAMUX_BASE,
        };

        AT_NONCACHEABLE_SECTION(lpspi_master_edma_handle_t lpspiEdmaHandle);

        bool isInitialized = false;
        QueueHandle_t transferCompleteQueue;
        SemaphoreHandle_t busySemaphore; // Suspends the task until the EPD display is busy

        BspEinkDriver lpspiEdmaDriverState = {
            &lpspiResource,
            &lpspiEdmaResource,
            &lpspiEdmaHandle,
            nullptr, // Will be filled in init function
            nullptr, // Will be filled in init function
            0,
            0,
            nullptr,
            SPICSConfig::Automatic,
            BusyWaitEventState::Registered,
        };

        void lpspiMasterEdmaCallback(LPSPI_Type *base,
                                     lpspi_master_edma_handle_t *handle,
                                     status_t status,
                                     void *userData)
        {
            BaseType_t xHigherPriorityTaskWoken = pdFALSE;

            if (xQueueSendFromISR(transferCompleteQueue, &status, &xHigherPriorityTaskWoken) != pdPASS) {
                /* If we reached this point, something very bad happened */
                return;
            }

            /* Disable SPI for current consumption reduction */
            LPSPI_Enable(lpspiBase, false);

            portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
        }
    } // namespace

    status_t init()
    {
        if (isInitialized) {
            return kStatus_Success;
        }

        /* If busy semaphore already created - delete it */
        if (busySemaphore != nullptr) {
            vSemaphoreDelete(busySemaphore);
        }

        /* Create new busy semaphore */
        busySemaphore = xSemaphoreCreateBinary();
        if (busySemaphore == nullptr) {
            return kStatus_Fail;
        }

        /* At the beginning the semaphore is in unknown state, it has to be clearly taken or given */
        xSemaphoreTake(busySemaphore, 0);

        /* If transfer complete queue already created - delete it */
        if (transferCompleteQueue != nullptr) {
            vQueueDelete(transferCompleteQueue);
        }

        /* Create new queue */
        transferCompleteQueue = xQueueCreate(1, sizeof(std::uint32_t));
        if (transferCompleteQueue == nullptr) {
            vSemaphoreDelete(busySemaphore);
            busySemaphore = nullptr;
            return kStatus_Fail;
        }

        auto lpspi           = &lpspiEdmaDriverState;
        lpspi->eventRegister = BusyWaitEventState::NotRegistered;

        gpio = DriverGPIO::Create(static_cast<GPIOInstances>(BoardDefinitions::EINK_GPIO), DriverGPIOParams{});
        eink_gpio_configure();

        LPSPI_MasterGetDefaultConfig(&spi_config);
        spi_config.baudRate                      = transferWriteClockHz;
        spi_config.bitsPerFrame                  = 8;
        spi_config.cpol                          = kLPSPI_ClockPolarityActiveHigh;
        spi_config.cpha                          = kLPSPI_ClockPhaseFirstEdge;
        spi_config.direction                     = kLPSPI_MsbFirst;
        spi_config.pcsToSckDelayInNanoSec        = delayInNanoSec;
        spi_config.lastSckToPcsDelayInNanoSec    = delayInNanoSec;
        spi_config.betweenTransferDelayInNanoSec = delayInNanoSec;
        spi_config.whichPcs                      = kLPSPI_Pcs0;
        spi_config.pcsActiveHighOrLow            = kLPSPI_PcsActiveLow;
        spi_config.pinCfg                        = kLPSPI_SdiInSdoOut;
        spi_config.dataOutConfig                 = kLpspiDataOutRetained;

        LPSPI_MasterInit(lpspiBase, &spi_config, lpspiGetFreq());

        /* FSL LPSPI doesn't support configuring autopcs feature */
        lpspiBase->CFGR1 |= LPSPI_CFGR1_AUTOPCS(0);

        dmamux = DriverDMAMux::Create(static_cast<DMAMuxInstances>(BoardDefinitions::EINK_DMAMUX), {});
        dma    = DriverDMA::Create(static_cast<DMAInstances>(BoardDefinitions::EINK_DMA), {});

        txDMAHandle = dma->CreateHandle(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL));
        rxDMAHandle = dma->CreateHandle(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL));

        dmamux->Enable(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL),
                       BSP_EINK_LPSPI_DMA_TX_PERI_SEL); // TODO: M.P fix BSP_EINK_LPSPI_DMA_TX_PERI_SEL
        dmamux->Enable(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL),
                       BSP_EINK_LPSPI_DMA_RX_PERI_SEL); // TODO: M.P fix BSP_EINK_LPSPI_DMA_RX_PERI_SEL

        lpspiEdmaDriverState.edmaTxDataToTxRegHandle = reinterpret_cast<edma_handle_t *>(txDMAHandle->GetHandle());
        lpspiEdmaDriverState.edmaRxRegToRxDataHandle = reinterpret_cast<edma_handle_t *>(rxDMAHandle->GetHandle());

        LPSPI_SetMasterSlaveMode(lpspiBase, kLPSPI_Master);
        LPSPI_MasterTransferCreateHandleEDMA(lpspiBase,
                                             lpspi->handle,
                                             lpspiMasterEdmaCallback,
                                             nullptr,
                                             lpspi->edmaRxRegToRxDataHandle,
                                             lpspi->edmaTxDataToTxRegHandle);

        isInitialized = true;
        return kStatus_Success;
    }

    void deinit()
    {
        if (!isInitialized) {
            return;
        }

        LPSPI_Enable(lpspiBase, false);

        if (busySemaphore != nullptr) {
            vSemaphoreDelete(busySemaphore);
            busySemaphore = nullptr;
        }

        if (transferCompleteQueue != nullptr) {
            vQueueDelete(transferCompleteQueue);
            transferCompleteQueue = nullptr;
        }

        dmamux->Disable(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL));
        dmamux->Disable(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL));
        dmamux.reset();
        dma.reset();

        gpio->DisableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
        gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
        gpio.reset();

        isInitialized = false;
    }

    void logicPowerOn()
    {
        eink_gpio_power_on();
    }

    void logicPowerOff()
    {
        eink_gpio_power_off();
    }

    void writeCS(SPICSState csState)
    {
        gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_CS_PIN), static_cast<std::uint8_t>(csState));
    }

    bool waitUntilDisplayBusy(std::uint32_t timeout)
    {
        bool success                       = false;
        lpspiEdmaDriverState.eventRegister = BusyWaitEventState::Registered;
        if (xSemaphoreTake(busySemaphore, timeout) != pdPASS) {
            success = false;
        }
        else {
            xSemaphoreGive(busySemaphore);
            success = true;
        }

        lpspiEdmaDriverState.eventRegister = BusyWaitEventState::NotRegistered;
        return success;
    }

    void resetDisplayController()
    {
        writeCS(SPICSState::Set);

        gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_RESET_PIN), 0);
        vTaskDelay(pdMS_TO_TICKS(10));
        gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_RESET_PIN), 1);
        vTaskDelay(pdMS_TO_TICKS(10));
    }

    status_t changeSpiFrequency(std::uint32_t frequencyHz)
    {
        std::uint32_t tcrPrescalerValue = 0;

        LPSPI_Enable(lpspiBase, false);
        LPSPI_MasterSetBaudRate(lpspiBase, frequencyHz, lpspiGetFreq(), &tcrPrescalerValue);

        spi_config.baudRate = frequencyHz;
        lpspiBase->TCR      = LPSPI_TCR_CPOL(spi_config.cpol) | LPSPI_TCR_CPHA(spi_config.cpha) |
                         LPSPI_TCR_LSBF(spi_config.direction) | LPSPI_TCR_FRAMESZ(spi_config.bitsPerFrame - 1U) |
                         LPSPI_TCR_PRESCALE(tcrPrescalerValue) | LPSPI_TCR_PCS(spi_config.whichPcs);

        return 0;
    }

    status_t writeData(void *txBuffer, std::uint32_t len, SPICSConfig csMode)
    {
        constexpr auto txTimeoutMs = 2000U;

        status_t tx_status = -1;
        status_t status;
        lpspi_transfer_t xfer{};

        if (csMode == SPICSConfig::Automatic) {
            writeCS(SPICSState::Clear);
        }

        /* Increase the SPI clock frequency to the SPI WRITE value */
        changeSpiFrequency(transferWriteClockHz);

        lpspiEdmaDriverState.csConfig         = csMode;
        lpspiEdmaDriverState.handle->userData = &lpspiEdmaDriverState;

        /* Clean Tx complete queue */
        xQueueReset(transferCompleteQueue);

        /* Clear BUSY Pin IRQ Flag */
        gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

        /* Enable BUSY Pin IRQ */
        gpio->EnableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

        /* Take the BUSY semaphore without timeout just in case the transmission makes the BUSY pin state change. It
         * enables the driver to block then on the busySemaphore until the BUSY pin is deasserted. */
        xSemaphoreTake(busySemaphore, 0);

        const std::uint8_t loopCnt = (len / (DMA_MAX_SINGLE_TRANSACTION_PAYLOAD + 1)) + 1;
        std::uint32_t frameSize    = 0;
        std::uint32_t bytesSent    = 0;

        for (std::uint8_t i = 0; i < loopCnt; ++i) {
            /* The MAJOR loop of the DMA can have maximum value of 32767 */
            if (len > DMA_MAX_SINGLE_TRANSACTION_PAYLOAD) {
                frameSize = DMA_MAX_SINGLE_TRANSACTION_PAYLOAD;
            }
            else {
                frameSize = len;
            }

            xfer.rxData      = nullptr;
            xfer.txData      = reinterpret_cast<std::uint8_t *>(txBuffer) + bytesSent;
            xfer.dataSize    = frameSize;
            xfer.configFlags = kLPSPI_MasterByteSwap | kLPSPI_MasterPcsContinuous;

            SCB_CleanInvalidateDCache();
            status = LPSPI_MasterTransferEDMA(lpspiEdmaDriverState.resource->base, lpspiEdmaDriverState.handle, &xfer);
            if (status != kStatus_Success) {
                /* In case of error just flush transfer complete queue */
                xQueueReset(transferCompleteQueue);

                if (csMode == SPICSConfig::Automatic) {
                    writeCS(SPICSState::Set);
                }
                return status;
            }
            else {
                if (xQueueReceive(transferCompleteQueue, &tx_status, pdMS_TO_TICKS(txTimeoutMs)) != pdPASS) {
                    /* Something very bad happened */
                    if (csMode == SPICSConfig::Automatic) {
                        writeCS(SPICSState::Set);
                    }
                    return -1;
                }
            }

            bytesSent += frameSize;
            len -= frameSize;
        }

        if (csMode == SPICSConfig::Automatic) {
            writeCS(SPICSState::Set);
        }
        return tx_status;
    }

    status_t readData(void *rxBuffer, std::uint32_t len, SPICSConfig csMode)
    {
        constexpr auto rxTimeoutMs = 2000U;

        status_t tx_status = -1;
        status_t status;
        lpspi_transfer_t xfer{};

        xfer.txData      = nullptr;
        xfer.rxData      = reinterpret_cast<std::uint8_t *>(rxBuffer);
        xfer.dataSize    = len;
        xfer.configFlags = kLPSPI_MasterByteSwap | kLPSPI_MasterPcsContinuous;

        if (csMode == SPICSConfig::Automatic) {
            writeCS(SPICSState::Clear);
        }

        /* Slow down the SPI clock for the value proper for the read operation */
        changeSpiFrequency(transferReadClockHz);

        lpspiEdmaDriverState.csConfig         = csMode;
        lpspiEdmaDriverState.handle->userData = &lpspiEdmaDriverState;

        /* Clean TX complete queue */
        xQueueReset(transferCompleteQueue);

        /* Clear BUSY Pin IRQ Flag */
        gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

        /* Enable BUSY Pin IRQ */
        gpio->EnableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

        /* Take the BUSY semaphore without timeout just in case the transmission makes the BUSY pin state change. It
         * enables the driver to block then on the busySemaphore until the BUSY pin is deasserted. */
        xSemaphoreTake(busySemaphore, 0);

        status = LPSPI_MasterTransferEDMA(lpspiEdmaDriverState.resource->base, lpspiEdmaDriverState.handle, &xfer);
        if (status != kStatus_Success) {
            /* In case of error just flush transfer complete queue */
            std::uint32_t dummy = 0;
            xQueueReceive(transferCompleteQueue, &dummy, 0);
            if (csMode == SPICSConfig::Automatic) {
                writeCS(SPICSState::Set);
            }
            return status;
        }
        else {
            if (xQueueReceive(transferCompleteQueue, &tx_status, pdMS_TO_TICKS(rxTimeoutMs)) != pdPASS) {
                /* Something very bad happened */
                if (csMode == SPICSConfig::Automatic) {
                    writeCS(SPICSState::Set);
                }
                return -1;
            }
        }

        if (csMode == SPICSConfig::Automatic) {
            writeCS(SPICSState::Set);
        }

        return tx_status;
    }

    BaseType_t busyPinStateChangeHandler()
    {
        BaseType_t xHigherPriorityTaskWoken = pdFALSE;

        /* Give semaphore only if something is waiting for it */
        if (lpspiEdmaDriverState.eventRegister == BusyWaitEventState::Registered) {
            gpio->DisableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

            if (xSemaphoreGiveFromISR(busySemaphore, &xHigherPriorityTaskWoken) != pdPASS) {
                /* We should never reach this point */
            }

            /* Call user defined "eink not busy" event */
            if (lpspiEdmaDriverState.event != nullptr) {
                lpspiEdmaDriverState.event();
            }
        }

        /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
          exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
        __DSB();
#endif

        return xHigherPriorityTaskWoken;
    }
} // namespace bsp::eink

A module-bsp/board/rt1051/bsp/eink/BspEink.hpp => module-bsp/board/rt1051/bsp/eink/BspEink.hpp +43 -0
@@ 0,0 1,43 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#pragma once

#include <cstdint>
#include "fsl_common.h"
#include "FreeRTOS.h"

namespace bsp::eink
{
    using BusyEventCallback = void (*)();

    inline constexpr auto busyTimeoutMs = 3000U;

    enum class SPICSConfig
    {
        Automatic,
        Manual
    };

    enum class SPICSState
    {
        Clear = 0,
        Set   = 1
    };

    status_t init();
    void deinit();

    void logicPowerOn();
    void logicPowerOff();

    void writeCS(SPICSState csState);
    bool waitUntilDisplayBusy(std::uint32_t timeout);
    void resetDisplayController();

    status_t changeSpiFrequency(std::uint32_t frequencyHz);
    status_t writeData(void *txBuffer, std::uint32_t len, SPICSConfig csMode);
    status_t readData(void *rxBuffer, std::uint32_t len, SPICSConfig csMode);

    BaseType_t busyPinStateChangeHandler();
} // namespace bsp::eink

M module-bsp/board/rt1051/bsp/eink/ED028TC1.cpp => module-bsp/board/rt1051/bsp/eink/ED028TC1.cpp +434 -1246
@@ 1,1352 1,540 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#include "ED028TC1.h"
#include "ED028TC1.hpp"
#include "EinkDimensions.hpp"
#include "macros.h"
#include "bsp_eink.h"
#include "eink_dimensions.hpp"
#include "eink_binarization_luts.h"

#include <math.h>
#include "BspEink.hpp"
#include "EinkBufferTransformation.hpp"

#include <task.h>
#include <cstring>
#include <memory>
#include <log/log.hpp>
#include "board/BoardDefinitions.hpp"

#define EPD_BOOSTER_START_PERIOD_10MS 0
#define EPD_BOOSTER_START_PERIOD_20MS 1
#define EPD_BOOSTER_START_PERIOD_30MS 2
#define EPD_BOOSTER_START_PERIOD_40MS 3
#define EPD_BOOSTER_START_PERIOD_POS  6

#define EPD_BOOSTER_DRIVING_STRENGTH_1   0
#define EPD_BOOSTER_DRIVING_STRENGTH_2   1
#define EPD_BOOSTER_DRIVING_STRENGTH_3   2
#define EPD_BOOSTER_DRIVING_STRENGTH_4   3
#define EPD_BOOSTER_DRIVING_STRENGTH_5   4
#define EPD_BOOSTER_DRIVING_STRENGTH_6   5
#define EPD_BOOSTER_DRIVING_STRENGTH_7   6
#define EPD_BOOSTER_DRIVING_STRENGTH_8   7
#define EPD_BOOSTER_DRIVING_STRENGTH_POS 3

#define EPD_BOOSTER_OFF_TIME_GDR_0_27uS 0
#define EPD_BOOSTER_OFF_TIME_GDR_0_34uS 1
#define EPD_BOOSTER_OFF_TIME_GDR_0_40uS 2
#define EPD_BOOSTER_OFF_TIME_GDR_0_54uS 3
#define EPD_BOOSTER_OFF_TIME_GDR_0_80uS 4
#define EPD_BOOSTER_OFF_TIME_GDR_1_54uS 5
#define EPD_BOOSTER_OFF_TIME_GDR_3_34uS 6
#define EPD_BOOSTER_OFF_TIME_GDR_6_58uS 7
#define EPD_BOOSTER_OFF_TIME_GDR_POS    0

#define EINK_BLACK_PIXEL_MASK      0x00 // This is the mask for the black pixel value
#define EINK_1BPP_WHITE_PIXEL_MASK 0x01 // This is the mask for the white pixel in 1bpp mode
#define EINK_2BPP_WHITE_PIXEL_MASK 0x03 // This is the mask for the white pixel in 2bpp mode
#define EINK_4BPP_WHITE_PIXEL_MASK 0x0F // This is the mask for the white pixel in 4bpp mode

/* Internal variable definitions */
static bool s_einkIsPoweredOn = false; //  Variable which contains the state of the power of the EPD display

static EinkWaveforms_e s_einkConfiguredWaveform =
    EinkWaveformGC16; //  This variable contains the current waveform set in the display

static CACHEABLE_SECTION_SDRAM(uint8_t s_einkServiceRotatedBuf[BOARD_EINK_DISPLAY_RES_X * BOARD_EINK_DISPLAY_RES_Y / 2 +
                                                               2]); // Plus 2 for the EPD command and BPP config

/**
 * @brief This lut is used for convertion of the 4bp input grayscale pixel to the 1bpp output pixel
 */
static std::uint8_t s_einkMaskLut_1Bpp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1};

/**
 * @brief This lut is used for convertion of the 4bp input grayscale pixel to the 2bpp output pixel
 */
static std::uint8_t s_einkMaskLut_2Bpp[16] = {0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3};

/* External variable definitions */

/* Internal function prototypes */

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 1Bpp image
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformFrameCoordinateSystem_1Bpp(const std::uint8_t *dataIn,
                                                               std::uint16_t windowWidthPx,
                                                               std::uint16_t windowHeightPx,
                                                               std::uint8_t *dataOut,
                                                               EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 2Bpp image
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformFrameCoordinateSystem_2Bpp(const std::uint8_t *dataIn,
                                                               std::uint16_t windowWidthPx,
                                                               std::uint16_t windowHeightPx,
                                                               std::uint8_t *dataOut,
                                                               EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 3Bpp image
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformFrameCoordinateSystem_3Bpp(const std::uint8_t *dataIn,
                                                               std::uint16_t windowWidthPx,
                                                               std::uint16_t windowHeightPx,
                                                               std::uint8_t *dataOut,
                                                               EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 4Bpp image
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformFrameCoordinateSystem_4Bpp(const std::uint8_t *dataIn,
                                                               std::uint16_t windowWidthPx,
                                                               std::uint16_t windowHeightPx,
                                                               std::uint8_t *dataOut,
                                                               EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 1Bpp image. It also makes sure that the image is black and white only
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_1Bpp(const std::uint8_t *dataIn,
                                                                        std::uint16_t windowWidthPx,
                                                                        std::uint16_t windowHeightPx,
                                                                        std::uint8_t *dataOut,
                                                                        EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 2Bpp image. It also makes sure that the image is black and white only
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_2Bpp(const std::uint8_t *dataIn,
                                                                        std::uint16_t windowWidthPx,
                                                                        std::uint16_t windowHeightPx,
                                                                        std::uint8_t *dataOut,
                                                                        EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 3Bpp image. It also makes sure that the image is black and white only
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */
static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_3Bpp(const std::uint8_t *dataIn,
                                                                        std::uint16_t windowWidthPx,
                                                                        std::uint16_t windowHeightPx,
                                                                        std::uint8_t *dataOut,
                                                                        EinkDisplayColorMode_e invertColors);

/**
 *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by the
 * ED028TC1 display.
 *
 *  @note IT ROTATES only the 4Bpp image. It also makes sure that the image is black and white only
 *
 *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
 * single pixel
 *  @param uint16_t x               [in]  - x coordinate of image in pixels
 *  @param uint16_t y               [in]  - y coordinate of image in pixels
 *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
 *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
 *  @param uint8_t* dataOut         [out] - the buffer for rotated image
 *  @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
 *
 * @note Assumed dataIn coordinate system is the standard image coordinates system:
 *
 *   (0,0)   X
 *       *-------->
 *       |
 *     Y |
 *       |
 *       v
 *
 *
 * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very same
 * way in its own coordinate system which is:
 *
 *              displayWidth
 *                 _______  ^
 *                |       | |
 *                |       | |
 *  displayHeight |       | |
 *                |       | |
 *                |_______| |  X
 *                   \ /    |
 *    signal tape -  | |    |
 *                          |
 *                 <--------*
 *                    Y     (0,0)
 *
 * @return
 */

/*
 * Not rotating version of s_EinkTransformAnimationFrameCoordinateSystem_4Bpp.
 * It is used when EINK_ROTATE_90_CLOCKWISE is not defined.
 */

static std::uint8_t *s_EinkTransformFrameCoordinateSystemNoRotation_4Bpp(const std::uint8_t *dataIn,
                                                                         std::uint16_t windowWidthPx,
                                                                         std::uint16_t windowHeightPx,
                                                                         std::uint8_t *dataOut,
                                                                         EinkDisplayColorMode_e invertColors);

/* Function bodies */

void EinkChangeDisplayUpdateTimings(EinkDisplayTimingsMode_e timingsMode)

namespace bsp::eink
{
    char tmpbuf[4];
    tmpbuf[0] = EinkTCONSetting; // 0x60

    switch (timingsMode) {
    case EinkDisplayTimingsFastRefreshMode: {
        tmpbuf[1] = 0x10;
        tmpbuf[2] = 0x08;
        tmpbuf[3] = 0x08;
    } break;

    case EinkDisplayTimingsHighContrastMode: {
        tmpbuf[1] = 0x3F;
        tmpbuf[2] = 0x09;
        tmpbuf[3] = 0x2D;
    } break;

    case EinkDisplayTimingsDeepCleanMode: {
        tmpbuf[1] = 0x3F;
        tmpbuf[2] = 0x09;
        tmpbuf[3] = 0x50;
    } break;
    }
    namespace
    {
        constexpr std::uint8_t tconSettings[] = {0x3F, 0x09, 0x2D}; // Magic numbers we got from EInk
        constexpr std::size_t imageBufferSize =
            EINK_IMAGE_CONFIG_SIZE +
            ((BOARD_EINK_DISPLAY_RES_X * BOARD_EINK_DISPLAY_RES_Y) / (EINK_BITS_IN_BYTE / EINK_MAX_BPP));

        CACHEABLE_SECTION_SDRAM(std::uint8_t einkRotatedBuf[imageBufferSize]);

        auto poweredOn                   = false;              // Power state of EPD display
        auto currentlyConfiguredWaveform = EinkWaveform::GC16; // Current waveform set in the display

        void setGateOrder()
        {
            std::uint8_t buf[3];

            /* Set the order of gate refreshing */
            buf[0] = EinkGDOrderSetting;
            buf[1] = 0x02; // Magic value required by the ED028TC1 display manufacturer
            buf[2] = 0x00;
            if (writeData(buf, sizeof(buf), SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return;
            }
        }

    if (BSP_EinkWriteData(tmpbuf, sizeof(tmpbuf), SPI_AUTOMATIC_CS) != 0) {
        return;
    }
}
        EinkStatus setInitialConfig()
        {
            std::uint8_t buf[10];

            buf[0] = EinkPowerSetting; // 0x01
            buf[1] = 0x03;
            buf[2] = 0x04;
            buf[3] = 0x00; // 0x06
            buf[4] = 0x00;
            if (writeData(buf, 5, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

bool EinkIsPoweredOn()
{
    return s_einkIsPoweredOn;
}
            buf[0] = EinkPanelSetting;      // 0x00
            buf[1] = LUT_SEL | SHL | RST_N; // 0x25 -> _XON _RES0 LUT_SEL _DM - SHL _SPIWM RST_N
                                            // If 0x35 (DM - 1 is used (2bpp)) the SPI speed can be 25MHz
            buf[2] = 0x00;
            if (writeData(buf, 3, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

EinkStatus_e EinkPowerOn()
{
    if (s_einkIsPoweredOn) {
        return EinkOK;
    }
            buf[0] = EinkPowerSaving; // 0x26
            buf[1] = 0x82;            // B2
            if (writeData(buf, 2, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    std::uint8_t cmd = EinkPowerON; // 0x04
    if (BSP_EinkWriteData(&cmd, sizeof(cmd), SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
            buf[0] = EinkPowerOFFSequenceSetting; // 0x03
            buf[1] = 0x01;                        // 0x00;//0x03;
            if (writeData(buf, 2, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    s_einkIsPoweredOn = true;
            buf[0] = EinkBoosterSoftStart; // 0x07
            buf[1] = (EPD_BOOSTER_OFF_TIME_GDR_6_58uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                     (EPD_BOOSTER_DRIVING_STRENGTH_6 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                     (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);

            buf[2] = (EPD_BOOSTER_OFF_TIME_GDR_6_58uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                     (EPD_BOOSTER_DRIVING_STRENGTH_6 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                     (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);

            buf[3] = (EPD_BOOSTER_OFF_TIME_GDR_0_40uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                     (EPD_BOOSTER_DRIVING_STRENGTH_7 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                     (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);
            if (writeData(buf, 4, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    if (BSP_EinkWaitUntilDisplayBusy(pdMS_TO_TICKS(BSP_EinkBusyTimeout)) == 0) {
        return EinkTimeout;
    }
            buf[0] = EinkPLLControl; // 0x30
            buf[1] = 0x0E;
            if (writeData(buf, 2, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    return EinkOK;
}
            buf[0] = EinkTemperatureSensorSelection;       // Temp. sensor setting TSE
            buf[1] = EINK_TEMPERATURE_SENSOR_USE_INTERNAL; // Temperature offset
            buf[2] = 0x00;                                 // Host forced temperature value
            if (writeData(buf, 3, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

EinkStatus_e EinkPowerOff()
{
    if (!s_einkIsPoweredOn) {
        return EinkOK;
    }
            buf[0] = EinkVcomAndDataIntervalSetting; // 0x50
            buf[1] = DDX;                            // 0x01;   // 0x0D
            buf[2] = 0x00;                           // 0x22;
            if (writeData(buf, 3, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    std::uint8_t cmd = EinkPowerOFF; // 0x02
    if (BSP_EinkWriteData(&cmd, sizeof(cmd), SPI_AUTOMATIC_CS) != 0) {
        return EinkDMAErr;
    }
            buf[0] = EinkTCONSetting; // 0x60
            std::memcpy(&buf[1], tconSettings, sizeof(tconSettings));
            if (writeData(buf, 4, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    const auto ret = BSP_EinkWaitUntilDisplayBusy(pdMS_TO_TICKS(BSP_EinkBusyTimeout)) == 1 ? EinkOK : EinkTimeout;
            buf[0] = EinkResolutionSetting; // 0x61
            buf[1] = 0x02;                  // 0x02
            buf[2] = 0x60;                  // 0x60
            buf[3] = 0x01;                  // 0x01
            buf[4] = 0xE0;                  // 0xE0
            if (writeData(buf, 5, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }

    // continue procedure regardless result
    BSP_EinkLogicPowerOff();
            buf[0] = EinkVCM_DCSetting; // 0x82
            buf[1] = 0x30;
            if (writeData(buf, 2, SPICSConfig::Automatic) != kStatus_Success) {
                powerDown();
                return EinkStatus::DMAErr;
            }
            return EinkStatus::OK;
        }

    s_einkIsPoweredOn = false;
    return ret;
}
        EinkStatus readFlagsRegister(std::uint16_t *flags)
        {
            std::uint8_t cmd = EinkFLG;

EinkStatus_e EinkPowerDown(void)
{
    const auto powerOffStatus = EinkPowerOff();
    BSP_EinkDeinit();
    return powerOffStatus;
}
            writeCS(SPICSState::Clear);

std::int16_t EinkGetTemperatureInternal()
{
    std::uint8_t cmd;
    std::int8_t temp[2] = {0, 0};
            if (writeData(&cmd, sizeof(cmd), SPICSConfig::Manual) != kStatus_Success) {
                writeCS(SPICSState::Set);
                powerDown();
                return EinkStatus::DMAErr;
            }

    cmd = EinkTemperatureSensorCalibration;
            if (readData(flags, sizeof(*flags), SPICSConfig::Manual) != kStatus_Success) {
                writeCS(SPICSState::Set);
                powerDown();
                return EinkStatus::DMAErr;
            }

    BSP_EinkWriteCS(BSP_Eink_CS_Clr);
            writeCS(SPICSState::Set);

    if (BSP_EinkWriteData(&cmd, sizeof(cmd), SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return -1;
    }
            return EinkStatus::OK;
        }
    } // namespace

    void setDisplayRefreshTimings()
    {
        std::uint8_t buf[4];

    if (BSP_EinkWaitUntilDisplayBusy(pdMS_TO_TICKS(BSP_EinkBusyTimeout)) == 0) {
        return -1;
        buf[0] = EinkTCONSetting; // 0x60
        std::memcpy(&buf[1], tconSettings, sizeof(tconSettings));

        if (writeData(buf, sizeof(buf), SPICSConfig::Automatic) != kStatus_Success) {
            return;
        }
    }

    if (BSP_EinkReadData(temp, sizeof(temp), SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return -1;
    bool isPoweredOn()
    {
        return poweredOn;
    }

    BSP_EinkWriteCS(BSP_Eink_CS_Set);
    EinkStatus powerOn()
    {
        if (poweredOn) {
            return EinkStatus::OK;
        }

    // First byte of the temp describes the integer part of the temperature in degrees Celsius
    const std::int8_t temperatureInteger = temp[0];
    // The MSB bit of the second byte describes the fraction of the temperature. Bit value of 1 means .5 degree Celsius,
    // bit value of 0 means .0 degree Celsius
    // int8_t temperatureFraction =    ((temp[1] & 0x80) >> 7);
        std::uint8_t cmd = EinkPowerON; // 0x04
        if (writeData(&cmd, sizeof(cmd), SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

    return temperatureInteger;
}
        poweredOn = true;

static void s_EinkSetGateOrder()
{
    std::uint8_t buf[3];

    // Set the order of gate refreshing
    buf[0] = EinkGDOrderSetting;
    buf[1] = 0x02; // Magic value required by the ED028TC1 display manufacturer
    buf[2] = 0x00;
    if (BSP_EinkWriteData(buf, sizeof(buf), SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return;
    }
}
        if (!waitUntilDisplayBusy(pdMS_TO_TICKS(busyTimeoutMs))) {
            return EinkStatus::Timeout;
        }

static EinkStatus_e s_EinkSetInitialConfig()
{
    // send initialization data
    unsigned char tmpbuf[10];

    tmpbuf[0] = EinkPowerSetting; // 0x01
    tmpbuf[1] = 0x03;
    tmpbuf[2] = 0x04;
    tmpbuf[3] = 0x00; // 0x06
    tmpbuf[4] = 0x00;
    if (BSP_EinkWriteData(tmpbuf, 5, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
        return EinkStatus::OK;
    }

    tmpbuf[0] = EinkPanelSetting;      // 0x00
    tmpbuf[1] = LUT_SEL | SHL | RST_N; // 0x25 -> _XON _RES0 LUT_SEL _DM - SHL _SPIWM RST_N
                                       // If 0x35 (DM - 1 is used (2bpp)) the SPI speed can be 25MHz
    tmpbuf[2] = 0x00;
    if (BSP_EinkWriteData(tmpbuf, 3, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
    EinkStatus powerOff()
    {
        if (!poweredOn) {
            return EinkStatus::OK;
        }

    tmpbuf[0] = EinkPowerSaving; // 0x26
    tmpbuf[1] = 0x82;            // B2
    if (BSP_EinkWriteData(tmpbuf, 2, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        std::uint8_t cmd = EinkPowerOFF; // 0x02
        if (writeData(&cmd, sizeof(cmd), SPICSConfig::Automatic) != kStatus_Success) {
            return EinkStatus::DMAErr;
        }

    tmpbuf[0] = EinkPowerOFFSequenceSetting; // 0x03
    tmpbuf[1] = 0x01;                        // 0x00;//0x03;
    if (BSP_EinkWriteData(tmpbuf, 2, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        const auto ret = waitUntilDisplayBusy(pdMS_TO_TICKS(busyTimeoutMs)) ? EinkStatus::OK : EinkStatus::Timeout;

    tmpbuf[0] = EinkBoosterSoftStart; // 0x07
    tmpbuf[1] = (EPD_BOOSTER_OFF_TIME_GDR_6_58uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                (EPD_BOOSTER_DRIVING_STRENGTH_6 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);

    tmpbuf[2] = (EPD_BOOSTER_OFF_TIME_GDR_6_58uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                (EPD_BOOSTER_DRIVING_STRENGTH_6 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);

    tmpbuf[3] = (EPD_BOOSTER_OFF_TIME_GDR_0_40uS << EPD_BOOSTER_OFF_TIME_GDR_POS) |
                (EPD_BOOSTER_DRIVING_STRENGTH_7 << EPD_BOOSTER_DRIVING_STRENGTH_POS) |
                (EPD_BOOSTER_START_PERIOD_10MS << EPD_BOOSTER_START_PERIOD_POS);
    if (BSP_EinkWriteData(tmpbuf, 4, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        /* Continue procedure regardless result */
        logicPowerOff();
        poweredOn = false;

    tmpbuf[0] = EinkPLLControl; // 0x30
    tmpbuf[1] = 0x0E;
    if (BSP_EinkWriteData(tmpbuf, 2, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
        return ret;
    }

    tmpbuf[0] = EinkTemperatureSensorSelection;              // Temp. sensor setting TSE
    tmpbuf[1] = EINK_TEMPERATURE_SENSOR_USE_INTERNAL | 0x00; // Temperature offset
    tmpbuf[2] = 0x00;                                        // Host forced temperature value
    if (BSP_EinkWriteData(tmpbuf, 3, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    EinkStatus powerDown()
    {
        const auto powerOffStatus = powerOff();
        deinit();
        return powerOffStatus;
    }

    tmpbuf[0] = EinkVcomAndDataIntervalSetting; // 0x50
    tmpbuf[1] = DDX;                            // 0x01;   // 0x0D
    tmpbuf[2] = 0x00;                           // 0x22;
    if (BSP_EinkWriteData(tmpbuf, 3, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
    std::int16_t getTemperatureInternal()
    {
        std::uint8_t cmd    = EinkTemperatureSensorCalibration;
        std::int8_t temp[2] = {0, 0};

    tmpbuf[0] = EinkTCONSetting; // 0x60
    tmpbuf[1] = 0x3F;
    tmpbuf[2] = 0x09;
    tmpbuf[3] = 0x2D;
    if (BSP_EinkWriteData(tmpbuf, 4, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        writeCS(SPICSState::Clear);

    tmpbuf[0] = EinkResolutionSetting; // 0x61
    tmpbuf[1] = 0x02;                  // 0x02
    tmpbuf[2] = 0x60;                  // 0x60
    tmpbuf[3] = 0x01;                  // 0x01
    tmpbuf[4] = 0xE0;                  // 0xE0
    if (BSP_EinkWriteData(tmpbuf, 5, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        if (writeData(&cmd, sizeof(cmd), SPICSConfig::Manual) != kStatus_Success) {
            writeCS(SPICSState::Set);
            powerDown();
            return -1;
        }

    tmpbuf[0] = EinkVCM_DCSetting; // 0x82
    tmpbuf[1] = 0x30;
    if (BSP_EinkWriteData(tmpbuf, 2, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
    return EinkOK;
}
        if (!waitUntilDisplayBusy(pdMS_TO_TICKS(busyTimeoutMs))) {
            return -1;
        }

EinkStatus_e EinkResetAndInitialize()
{
    BSP_EinkLogicPowerOn();
        if (readData(temp, sizeof(temp), SPICSConfig::Manual) != kStatus_Success) {
            writeCS(SPICSState::Set);
            powerDown();
            return -1;
        }

    // Initialize the synchronization resources, SPI and GPIOs for the Eink BSP
    if (BSP_EinkInit() != 0) {
        EinkPowerDown();
        return EinkInitErr;
    }
    // Reset the display
    BSP_EinkResetDisplayController();
    // Set the initial configuration of the eink registers after reset
    if (s_EinkSetInitialConfig() != EinkOK) {
        EinkPowerDown();
        return EinkInitErr;
    }
        writeCS(SPICSState::Set);

    // After the reset the display is powered off
    s_einkIsPoweredOn = false;
    return EinkOK;
}
        /* First byte of the temp describes the integer part of the temperature in degrees Celsius */
        const std::int8_t temperatureInteger = temp[0];

EinkStatus_e EinkUpdateWaveform(const EinkWaveformSettings_t *settings)
{
    /// LUTD
    if (BSP_EinkWriteData(settings->LUTDData, settings->LUTDSize, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        /* The MSB bit of the second byte describes the fraction of the temperature. Bit value of 1 means .5 degree
         * Celsius, bit value of 0 means .0 degree Celsius */
        // const std::int8_t temperatureFraction = ((temp[1] & 0x80) >> 7);

    /// LUTC
    if (BSP_EinkWriteData(settings->LUTCData, settings->LUTCSize + 1, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
        return temperatureInteger;
    }

    s_einkConfiguredWaveform = settings->mode;

    return EinkOK;
}
    EinkStatus resetAndInitialize()
    {
        logicPowerOn();

static EinkStatus_e s_EinkReadFlagsRegister(std::uint16_t *flags)
{
    std::uint8_t cmd = EinkFLG;
        /* Initialize the synchronization resources, SPI and GPIOs for the Eink BSP */
        if (init() != 0) {
            powerDown();
            return EinkStatus::InitErr;
        }

    BSP_EinkWriteCS(BSP_Eink_CS_Clr);
        /* Reset the display */
        resetDisplayController();

    if (BSP_EinkWriteData(&cmd, sizeof(cmd), SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return EinkDMAErr;
    }
        /* Set the initial configuration of the eink registers after reset */
        if (setInitialConfig() != EinkStatus::OK) {
            powerDown();
            return EinkStatus::InitErr;
        }

    if (BSP_EinkReadData(flags, sizeof(std::uint16_t), SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return EinkDMAErr;
        /* After the reset the display is powered off */
        poweredOn = false;
        return EinkStatus::OK;
    }

    BSP_EinkWriteCS(BSP_Eink_CS_Set);

    return EinkOK;
}
    EinkStatus updateWaveform(const EinkWaveformSettings *settings)
    {
        /* LUTD */
        if (writeData(settings->LUTDData, settings->LUTDSize, SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

EinkStatus_e EinkWaitTillPipelineBusy()
{
    std::uint16_t flags = 0;
        /* LUTC */
        if (writeData(settings->LUTCData, settings->LUTCSize + 1, SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

    s_EinkReadFlagsRegister(&flags);
        currentlyConfiguredWaveform = settings->mode;

    while ((flags & EINK_FLAG_PIPELINE_BUSY)) {
        vTaskDelay(pdMS_TO_TICKS(1));
        s_EinkReadFlagsRegister(&flags);
        return EinkStatus::OK;
    }

    return EinkOK;
}
    EinkStatus waitTillPipelineBusy()
    {
        std::uint16_t flags = 0;

EinkStatus_e EinkDitherDisplay()
{
    std::uint8_t cmdWithArgs[2] = {EinkDPC, EINK_DITHER_4BPP_MODE | EINK_DITHER_START};
        readFlagsRegister(&flags);
        while ((flags & EINK_FLAG_PIPELINE_BUSY)) {
            vTaskDelay(pdMS_TO_TICKS(1));
            readFlagsRegister(&flags);
        }

    if (BSP_EinkWriteData(cmdWithArgs, sizeof(cmdWithArgs), SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
        return EinkStatus::OK;
    }

    std::uint16_t flags = 0;
    EinkStatus ditherDisplay()
    {
        std::uint8_t cmdWithArgs[2] = {EinkDPC, EINK_DITHER_4BPP_MODE | EINK_DITHER_START};

    s_EinkReadFlagsRegister(&flags);
        if (writeData(cmdWithArgs, sizeof(cmdWithArgs), SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

    if ((flags & EINK_FLAG_DITHER_IN_PROGRESS)) {
        return EinkSPIErr;
    }
        std::uint16_t flags = 0;
        readFlagsRegister(&flags);
        if ((flags & EINK_FLAG_DITHER_IN_PROGRESS)) {
            return EinkStatus::SPIErr;
        }

    return EinkOK;
}
        return EinkStatus::OK;
    }

EinkStatus_e EinkUpdateFrame(EinkFrame_t frame,
                             const std::uint8_t *buffer,
                             EinkBpp_e bpp,
                             EinkDisplayColorMode_e invertColors)
{
    std::uint8_t buf[10];
    std::uint8_t pixelsInByte = 8 / bpp;

    s_einkServiceRotatedBuf[0] = EinkDataStartTransmission1;
    s_einkServiceRotatedBuf[1] = bpp - 1; //  0 - 1Bpp, 1 - 2Bpp, 2 - 3Bpp, 3 - 4Bpp

    if ((s_einkConfiguredWaveform == EinkWaveformA2) || (s_einkConfiguredWaveform == EinkWaveformDU2)) {
        switch (bpp) {
        case Eink1Bpp: {
            s_EinkTransformAnimationFrameCoordinateSystem_1Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink2Bpp: {
            s_EinkTransformAnimationFrameCoordinateSystem_2Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink3Bpp: {
            s_EinkTransformAnimationFrameCoordinateSystem_3Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink4Bpp: {
    EinkStatus updateFrame(EinkFrame frame, const std::uint8_t *buffer, EinkBpp bpp, EinkDisplayColorMode invertColors)
    {
        const std::uint8_t pixelsInByte = 8 / static_cast<unsigned>(bpp);
        std::uint8_t buf[10];

        einkRotatedBuf[0] = EinkDataStartTransmission1;
        einkRotatedBuf[1] = static_cast<unsigned>(bpp) - 1; //  0 - 1Bpp, 1 - 2Bpp, 2 - 3Bpp, 3 - 4Bpp

        if ((currentlyConfiguredWaveform == EinkWaveform::A2) || (currentlyConfiguredWaveform == EinkWaveform::DU2)) {
            switch (bpp) {
            case EinkBpp::Eink1Bpp:
                transformAnimationFrameCoordinateSystem1Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink2Bpp:
                transformAnimationFrameCoordinateSystem2Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink3Bpp:
                transformAnimationFrameCoordinateSystem3Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink4Bpp:
#if defined(EINK_ROTATE_90_CLOCKWISE)
            s_EinkTransformFrameCoordinateSystem_4Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
                transformFrameCoordinateSystem4Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
#else
            s_EinkTransformFrameCoordinateSystemNoRotation_4Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
                transformFrameCoordinateSystemNoRotation4Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
#endif
        } break;
                break;
            }
        }
    }
    else {
        switch (bpp) {
        case Eink1Bpp: {
            s_EinkTransformFrameCoordinateSystem_1Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink2Bpp: {
            s_EinkTransformFrameCoordinateSystem_2Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink3Bpp: {
            s_EinkTransformFrameCoordinateSystem_3Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
        } break;
        case Eink4Bpp: {
        else {
            switch (bpp) {
            case EinkBpp::Eink1Bpp:
                transformFrameCoordinateSystem1Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink2Bpp:
                transformFrameCoordinateSystem2Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink3Bpp:
                transformFrameCoordinateSystem3Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
                break;

            case EinkBpp::Eink4Bpp:
#if defined(EINK_ROTATE_90_CLOCKWISE)
            s_EinkTransformFrameCoordinateSystem_4Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
                transformFrameCoordinateSystem4Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
#else
            s_EinkTransformFrameCoordinateSystemNoRotation_4Bpp(
                buffer, frame.width, frame.height, s_einkServiceRotatedBuf + 2, invertColors);
                transformFrameCoordinateSystemNoRotation4Bpp(
                    buffer, frame.width, frame.height, &einkRotatedBuf[EINK_IMAGE_CONFIG_SIZE], invertColors);
#endif
        } break;
                break;
            }
        }
    }

    buf[0] = EinkDataStartTransmissionWindow; // set display window
    buf[1] = static_cast<std::uint8_t>(hal::eink::getDisplayXAxis(frame) >>
                                       8); // MSB of the X axis in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[2] = static_cast<std::uint8_t>(
        hal::eink::getDisplayXAxis(frame)); // LSB of the X axis in the EPD display. Value converted from
                                            // the standard GUI coords system to the ED028TC1 one
    buf[3] = static_cast<std::uint8_t>(hal::eink::getDisplayYAxis(frame) >>
                                       8); // MSB of the Y axis in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[4] = static_cast<std::uint8_t>(
        hal::eink::getDisplayYAxis(frame)); // LSB of the Y axis in the EPD display. Value converted from
                                            // the standard GUI coords system to the ED028TC1 one
    buf[5] = static_cast<std::uint8_t>(hal::eink::getDisplayWindowWidth(frame) >>
                                       8); // MSB of the window height in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[6] = static_cast<std::uint8_t>(
        hal::eink::getDisplayWindowWidth(frame)); // LSB of the window height in the EPD display. Value converted from
                                                  // the standard GUI coords system to the ED028TC1 one
    buf[7] = static_cast<std::uint8_t>(hal::eink::getDisplayWindowHeight(frame) >>
                                       8); // MSB of the window width in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[8] = static_cast<std::uint8_t>(
        hal::eink::getDisplayWindowHeight(frame)); // LSB of the window width in the EPD display. Value converted from
    // the standard GUI coords system to the ED028TC1 one

    if (BSP_EinkWriteData(buf, 9, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }

    std::uint32_t msgSize = 2 + (static_cast<std::uint32_t>(frame.width) * static_cast<std::uint32_t>(frame.height) /
                                 pixelsInByte); // command (1 byte) + bpp (1 byte) + dataSize(W*H/pixelsInByte bytes)
    // Send the part of the image to the display memory

    if (BSP_EinkWriteData(s_einkServiceRotatedBuf, msgSize, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }

    return (EinkOK);
}

EinkStatus_e EinkFillScreenWithColor(EinkDisplayColorFilling_e colorFill)
{
    std::uint8_t buf[10];

    // Set the window to the entire screen
    buf[0] = EinkDataStartTransmissionWindow; // 0x83
    buf[1] = 0x00;
    buf[2] = 0x00;
    buf[3] = 0x00;
    buf[4] = 0x00;
    buf[5] = (EINK_DISPLAY_RES_X & 0xFF00) >> 8;
    buf[6] = EINK_DISPLAY_RES_X & 0x00FF;
    buf[7] = (EINK_DISPLAY_RES_Y & 0xFF00) >> 8;
    buf[8] = EINK_DISPLAY_RES_Y & 0x00FF;

    if (BSP_EinkWriteData(buf, 9, SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }

    BSP_EinkWriteCS(BSP_Eink_CS_Clr);

    buf[0] = EinkDataStartTransmission1; // 0x10
    buf[1] = Eink1Bpp - 1;
    if (BSP_EinkWriteData(buf, 2, SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return EinkDMAErr;
    }

    std::uint8_t background = colorFill;

    std::unique_ptr<char[]> bg;
    try {
        bg = std::unique_ptr<char[]>(new char[BOARD_EINK_DISPLAY_RES_Y * BOARD_EINK_DISPLAY_RES_X / 8]);
    }
    catch (const std::bad_alloc &exception) {
        LOG_ERROR("Could not create the buffer for the background plane");
        return EinkNoMem;
    }

    memset(bg.get(), background, BOARD_EINK_DISPLAY_RES_Y * BOARD_EINK_DISPLAY_RES_X / 8);

    if (BSP_EinkWriteData(bg.get(), BOARD_EINK_DISPLAY_RES_Y * BOARD_EINK_DISPLAY_RES_X / 8, SPI_MANUAL_CS) != 0) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
        EinkPowerDown();
        return EinkDMAErr;
    }

    BSP_EinkWriteCS(BSP_Eink_CS_Set);
        /* Set display window */
        buf[0] = EinkDataStartTransmissionWindow;
        /* MSB of X axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[1] = static_cast<std::uint8_t>(getDisplayXAxis(frame) >> 8);
        /* LSB of X axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[2] = static_cast<std::uint8_t>(getDisplayXAxis(frame));
        /* MSB of Y axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[3] = static_cast<std::uint8_t>(getDisplayYAxis(frame) >> 8);
        /* LSB of Y axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[4] = static_cast<std::uint8_t>(getDisplayYAxis(frame));
        /* MSB of window height of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[5] = static_cast<std::uint8_t>(getDisplayWindowWidth(frame) >> 8);
        /* LSB of window height of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[6] = static_cast<std::uint8_t>(getDisplayWindowWidth(frame));
        /* MSB of window width of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[7] = static_cast<std::uint8_t>(getDisplayWindowHeight(frame) >> 8);
        /* LSB of window width of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[8] = static_cast<std::uint8_t>(getDisplayWindowHeight(frame));

        if (writeData(buf, 9, SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

    return EinkRefreshImage(EinkFrame_t{0, 0, BOARD_EINK_DISPLAY_RES_X, BOARD_EINK_DISPLAY_RES_Y},
                            EinkDisplayTimingsDeepCleanMode);
}
        /* Config (2 bytes) + dataSize (W * H / pixelsInByte bytes) */
        const auto msgSize = EINK_IMAGE_CONFIG_SIZE + (static_cast<std::uint32_t>(frame.width) *
                                                       static_cast<std::uint32_t>(frame.height) / pixelsInByte);

EinkStatus_e EinkRefreshImage(EinkFrame_t frame, EinkDisplayTimingsMode_e refreshTimingsMode)
{
    EinkChangeDisplayUpdateTimings(refreshTimingsMode);

    s_EinkSetGateOrder();

    std::uint8_t buf[10];

    buf[0] = EinkDisplayRefresh;
    buf[1] = UPD_CPY_TO_PRE;

    buf[2] = static_cast<std::uint8_t>(hal::eink::getDisplayXAxis(frame) >>
                                       8); // MSB of the X axis in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[3] = static_cast<std::uint8_t>(
        hal::eink::getDisplayXAxis(frame)); // LSB of the X axis in the EPD display. Value converted from
                                            // the standard GUI coords system to the ED028TC1 one
    buf[4] = static_cast<std::uint8_t>(hal::eink::getDisplayYAxis(frame) >>
                                       8); // MSB of the Y axis in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[5] = static_cast<std::uint8_t>(
        hal::eink::getDisplayYAxis(frame)); // LSB of the Y axis in the EPD display. Value converted from
                                            // the standard GUI coords system to the ED028TC1 one
    buf[6] = static_cast<std::uint8_t>(hal::eink::getDisplayWindowWidth(frame) >>
                                       8); // MSB of the window height in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[7] = static_cast<std::uint8_t>(
        hal::eink::getDisplayWindowWidth(frame)); // LSB of the window height in the EPD display. Value converted from
                                                  // the standard GUI coords system to the ED028TC1 one
    buf[8] = static_cast<std::uint8_t>(hal::eink::getDisplayWindowHeight(frame) >>
                                       8); // MSB of the window width in the EPD display. Value converted
                                           // from the standard GUI coords system to the ED028TC1 one
    buf[9] = static_cast<std::uint8_t>(
        hal::eink::getDisplayWindowHeight(frame)); // LSB of the window width in the EPD display. Value converted from
    // the standard GUI coords system to the ED028TC1 one

    if (BSP_EinkWriteData(buf, sizeof(buf), SPI_AUTOMATIC_CS) != 0) {
        EinkPowerDown();
        return EinkDMAErr;
    }
        /* Send the part of the image to the display memory */
        if (writeData(einkRotatedBuf, msgSize, SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

    if (BSP_EinkWaitUntilDisplayBusy(pdMS_TO_TICKS(BSP_EinkBusyTimeout)) == 0) {
        return EinkTimeout;
        return EinkStatus::OK;
    }

    return EinkOK;
}

__attribute__((optimize("O3"))) void EinkARGBToLuminance(const std::uint8_t *dataIn,
                                                         std::uint8_t *dataOut,
                                                         std::uint32_t displayWidth,
                                                         std::uint32_t displayHeight)
{
    std::uint8_t r, g, b;
    float fi;
    std::uint32_t *src;
    std::uint8_t *dst;

    src = (std::uint32_t *)dataIn;
    dst = (std::uint8_t *)dataOut;

    for (std::uint32_t i = 0; i < (displayWidth * displayHeight);
         i += 2) // increase by 8 pixels - 32bit word is 8 pixels in 4BPP
    EinkStatus fillScreenWithColor(EinkDisplayColorFilling colorFill)
    {
        *dst = 0x00000000;
        for (std::uint8_t j = 0; j < 8; j += 4) {
            r  = (std::uint8_t)((*(src)) >> 16);
            g  = (std::uint8_t)((*(src)) >> 8);
            b  = (std::uint8_t) * (src);
            fi = (r + g + b) / 3;

            *dst |= ((std::uint32_t)(floor(fi / 16))) << (4 - j);

            src++;
        std::uint8_t buf[10];

        // Set the window to the entire screen
        buf[0] = EinkDataStartTransmissionWindow; // 0x83
        buf[1] = 0x00;
        buf[2] = 0x00;
        buf[3] = 0x00;
        buf[4] = 0x00;
        buf[5] = (EINK_DISPLAY_RES_X & 0xFF00) >> 8;
        buf[6] = EINK_DISPLAY_RES_X & 0x00FF;
        buf[7] = (EINK_DISPLAY_RES_Y & 0xFF00) >> 8;
        buf[8] = EINK_DISPLAY_RES_Y & 0x00FF;

        if (writeData(buf, 9, SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }
        dst++;
    }
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformFrameCoordinateSystem_1Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 1bpp mode there are 8 pixels in the byte
    const std::uint8_t pixelsInByte = 8;

    std::uint8_t pixels    = 0;
    std::uint8_t *outArray = dataOut;

    for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
        for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time.
            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            // Use the LUT to convert the input pixel from 4bpp to 1bpp
            std::uint8_t firstPixel   = s_einkMaskLut_1Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t secondPixel  = s_einkMaskLut_1Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t thirdPixel   = s_einkMaskLut_1Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t fourthPixel  = s_einkMaskLut_1Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t fifthPixel   = s_einkMaskLut_1Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t sixthPixel   = s_einkMaskLut_1Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t seventhPixel = s_einkMaskLut_1Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t eightPixel   = s_einkMaskLut_1Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]];

            // Put the pixels in order: Most left positioned pixel at the most significant side of byte
            pixels = (firstPixel << 7) | (secondPixel << 6) | (thirdPixel << 5) | (fourthPixel << 4) |
                     (fifthPixel << 3) | (sixthPixel << 2) | (seventhPixel << 1) | (eightPixel << 0);

            if (invertColors) {
                pixels = ~pixels;
            }
        writeCS(SPICSState::Clear);

            *outArray = pixels;
            ++outArray;
        buf[0] = EinkDataStartTransmission1; // 0x10
        buf[1] = static_cast<unsigned>(EinkBpp::Eink1Bpp) - 1;
        if (writeData(buf, 2, SPICSConfig::Manual) != kStatus_Success) {
            writeCS(SPICSState::Set);
            powerDown();
            return EinkStatus::DMAErr;
        }
    }

    return dataOut;
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformFrameCoordinateSystem_2Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 2bpp mode there are 4 pixels in the byte
    const std::uint8_t pixelsInByte = 8;
    std::uint16_t pixels            = 0;
    std::uint16_t *outArray         = (std::uint16_t *)dataOut;
    std::uint8_t temp               = 0;

    for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
        for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time.
            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
            temp = (s_einkMaskLut_2Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]] << 6);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]] << 4);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]] << 2);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]] << 0);

            // Push the 4 pixels into the proper place in the uint16_t
            pixels = temp << 0;

            // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
            temp = (s_einkMaskLut_2Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]] << 6);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]] << 4);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]] << 2);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]] << 0);

            // Push the 4 pixels into the proper place in the uint16_t
            pixels |= temp << 8;

            if (invertColors) {
                pixels = ~pixels;
            }
        constexpr auto pixelsPerByte1Bpp    = 8;
        constexpr auto backgroundBufferSize = BOARD_EINK_DISPLAY_RES_Y * BOARD_EINK_DISPLAY_RES_X / pixelsPerByte1Bpp;
        const auto backgroundColor          = static_cast<std::uint8_t>(colorFill);

            *outArray = pixels;
            ++outArray;
        std::unique_ptr<std::uint8_t[]> backgroundBuffer;
        try {
            backgroundBuffer = std::make_unique<std::uint8_t[]>(backgroundBufferSize);
        }
    }

    return dataOut;
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformFrameCoordinateSystem_3Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // The 4bpp is coded the same way as the 3bpp
    return s_EinkTransformFrameCoordinateSystem_4Bpp(dataIn, windowWidthPx, windowHeightPx, dataOut, invertColors);
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_1Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 1bpp mode there are 8 pixels in the byte
    const std::uint8_t pixelsInByte = 8;
    std::uint8_t pixels             = 0;
    std::uint8_t *outArray          = dataOut;

    for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
        for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time.

            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            // Use the LUT to convert the input pixel from 4bpp to 1bpp
            std::uint8_t firstPixel   = s_einkMaskLut_1Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t secondPixel  = s_einkMaskLut_1Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t thirdPixel   = s_einkMaskLut_1Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t fourthPixel  = s_einkMaskLut_1Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t fifthPixel   = s_einkMaskLut_1Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t sixthPixel   = s_einkMaskLut_1Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t seventhPixel = s_einkMaskLut_1Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]];
            std::uint8_t eightPixel   = s_einkMaskLut_1Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]];

            // Put the pixels in order: Most left positioned pixel at the most significant side of byte
            pixels = (firstPixel << 7) | (secondPixel << 6) | (thirdPixel << 5) | (fourthPixel << 4) |
                     (fifthPixel << 3) | (sixthPixel << 2) | (seventhPixel << 1) | (eightPixel << 0);

            if (invertColors) {
                pixels = ~pixels;
            }

            *outArray = pixels;
            ++outArray;
        catch (const std::bad_alloc &exception) {
            LOG_ERROR("Could not create the buffer for the background plane");
            return EinkStatus::NoMem;
        }
    }

    return dataOut;
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_2Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 2bpp mode there are 4 pixels in the byte
    const std::uint8_t pixelsInByte = 8;
    std::uint16_t pixels            = 0;
    std::uint16_t *outArray         = (std::uint16_t *)dataOut;
    std::uint8_t temp               = 0;
    for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
        for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time.
            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
            temp = (s_einkMaskLut_2Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]] << 6);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]] << 4);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]] << 2);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]] << 0);

            // Use the LUT to binarize the 2bpp pixels value and push them into the proper place in the uint16_t
            pixels = einkBinarizationLUT_2bpp[temp] << 0;

            // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
            temp = (s_einkMaskLut_2Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]] << 6);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]] << 4);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]] << 2);
            temp |= (s_einkMaskLut_2Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]] << 0);

            // Use the LUT to binarize the 2bpp pixels value and push them into the proper place in the uint16_t
            pixels |= einkBinarizationLUT_2bpp[temp] << 8;
            if (invertColors) {
                pixels = ~pixels;
            }
        std::memset(backgroundBuffer.get(), backgroundColor, backgroundBufferSize);

            *outArray = pixels;
            ++outArray;
        if (writeData(backgroundBuffer.get(), backgroundBufferSize, SPICSConfig::Manual) != kStatus_Success) {
            writeCS(SPICSState::Set);
            powerDown();
            return EinkStatus::DMAErr;
        }
    }

    return dataOut;
}

__attribute__((optimize("O3"))) static std::uint8_t *s_EinkTransformAnimationFrameCoordinateSystem_3Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // The 4bpp is coded the same way as the 3bpp
    return s_EinkTransformFrameCoordinateSystem_4Bpp(dataIn, windowWidthPx, windowHeightPx, dataOut, invertColors);
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformFrameCoordinateSystem_4Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 3bpp and 4bpp modes there are 2 pixels in the byte. Using 8bpp to process the whole uint32_t at once for
    // faster execution
    const std::uint8_t pixelsInByte = 8;

    std::uint32_t pixels    = 0;
    std::uint32_t *outArray = (std::uint32_t *)dataOut;

    for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
        for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time. Using 8 pixels at a time for better performance
            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            std::uint8_t firstPixelPair =
                (dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X];
            std::uint8_t secondPixelPair =
                (dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X];
            std::uint8_t thirdPixelPair =
                (dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X];
            std::uint8_t fourthPixelPair =
                (dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X];

            // Put the pixels in the uint32_t for faster processing
            pixels = firstPixelPair | (secondPixelPair << 8) | (thirdPixelPair << 16) | (fourthPixelPair << 24);

            if (invertColors) {
                pixels = ~pixels;
            }
        writeCS(SPICSState::Set);

            // Put the pixels in order: Most left positioned pixel at the most significant side of byte
            *outArray = pixels;
            ++outArray;
        }
        return refreshImage(EinkFrame{0, 0, BOARD_EINK_DISPLAY_RES_X, BOARD_EINK_DISPLAY_RES_Y});
    }

    return dataOut;
}

__attribute__((optimize("O1"))) static std::uint8_t *s_EinkTransformFrameCoordinateSystemNoRotation_4Bpp(
    const std::uint8_t *dataIn,
    std::uint16_t windowWidthPx,
    std::uint16_t windowHeightPx,
    std::uint8_t *dataOut,
    EinkDisplayColorMode_e invertColors)
{
    // In 3bpp and 4bpp modes there are 2 pixels in the byte. Using 8bpp to process the whole uint32_t at once for
    // faster execution
    const std::uint8_t pixelsInByte = 8;

    std::uint32_t pixels    = 0;
    std::uint32_t *outArray = (std::uint32_t *)dataOut;
    std::int32_t inputRow   = 0;
    std::int32_t inputCol   = 0;

    for (inputRow = 0; inputRow < windowHeightPx; ++inputRow) {
        for (inputCol = windowWidthPx - 7; inputCol >= 0; inputCol -= pixelsInByte) {
            // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
            // performance.
            //       Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
            //       take considerable amount of time. Using 8 pixels at a time for better performance
            std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

            // Get 4x 2 adjacent pixels to process them as uint32_t for better execution timings
            std::uint8_t firstPixelPair  = (dataIn[index]) | (dataIn[index + 1] << 4);
            std::uint8_t secondPixelPair = (dataIn[index + 2]) | (dataIn[index + 3] << 4);
            std::uint8_t thirdPixelPair  = (dataIn[index + 4]) | (dataIn[index + 5] << 4);
            std::uint8_t fourthPixelPair = (dataIn[index + 6]) | (dataIn[index + 7] << 4);

            // Put the pixels in the uint32_t for faster processing
            pixels = (firstPixelPair << 24) | (secondPixelPair << 16) | (thirdPixelPair << 8) | (fourthPixelPair);

            if (invertColors) {
                pixels = ~pixels;
            }
    EinkStatus refreshImage(EinkFrame frame)
    {
        setDisplayRefreshTimings();
        setGateOrder();

        std::uint8_t buf[10];

        buf[0] = EinkDisplayRefresh;
        buf[1] = UPD_CPY_TO_PRE;

        /* MSB of X axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[2] = static_cast<std::uint8_t>(getDisplayXAxis(frame) >> 8);
        /* LSB of X axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[3] = static_cast<std::uint8_t>(getDisplayXAxis(frame));
        /* MSB of Y axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[4] = static_cast<std::uint8_t>(getDisplayYAxis(frame) >> 8);
        /* LSB of Y axis of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[5] = static_cast<std::uint8_t>(getDisplayYAxis(frame));
        // MSB of window height of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[6] = static_cast<std::uint8_t>(getDisplayWindowWidth(frame) >> 8);
        /* LSB of window height of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[7] = static_cast<std::uint8_t>(getDisplayWindowWidth(frame));
        /* MSB of window width of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[8] = static_cast<std::uint8_t>(getDisplayWindowHeight(frame) >> 8);
        /* LSB of window width of EPD display. Value converted from the standard GUI coords system to ED028TC1 one */
        buf[9] = static_cast<std::uint8_t>(getDisplayWindowHeight(frame));

        if (writeData(buf, sizeof(buf), SPICSConfig::Automatic) != kStatus_Success) {
            powerDown();
            return EinkStatus::DMAErr;
        }

            // Put the pixels in order: Most left positioned pixel at the most significant side of byte
            *outArray = pixels;
            ++outArray;
        if (!waitUntilDisplayBusy(pdMS_TO_TICKS(busyTimeoutMs))) {
            return EinkStatus::Timeout;
        }
    }

    return dataOut;
        return EinkStatus::OK;
    }
}

R module-bsp/board/rt1051/bsp/eink/ED028TC1.h => module-bsp/board/rt1051/bsp/eink/ED028TC1.hpp +111 -156
@@ 1,28 1,10 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

/**
 * @file ED028TC1.h
 * @author Lukasz Skrzypczak (l.skrzypczak@mudita.com)
 * @date Sep 6, 2017
 * @brief Header for EInk ED028TC1 electronic paper display driver
 * @copyright Copyright (C) 2017 mudita.com.
 * @details This is hardware specific electronic paper display ED028TC1 driver.
 */

/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __ED028TC1_H
#define __ED028TC1_H

#include "FreeRTOS.h"
#include "semphr.h"
#pragma once

#if defined(__cplusplus)
extern "C"
{
#endif /* __cplusplus */
#include <cstdint>

/* Exported macro ------------------------------------------------------------*/
/**
 * @brief ED028TC1 register definitions
 */


@@ 212,17 194,18 @@ extern "C"
#define EINK_DITHER_4BPP_MODE (0 << 1)
#define EINK_DITHER_2BPP_MODE (1 << 1)

// Flags
#define EINK_FLAG_BUSY_N 0x0001 ///< This flag informs that the driver is busy. 0 - busy, 1 - idle
#define EINK_FLAG_POWER_OFF_IN_PROGRESS                                                                                \
    0x0002 ///< This flag informs that the Power Off sequence is in progress. 1 - in progress
#define EINK_FLAG_POWER_ON_IN_PROGRESS                                                                                 \
    0x0004 ///< This flag informs that the Power On sequence is in progress. 1 - in progress
#define EINK_FLAG_ENTIRE_FRAME_RECEIVED                                                                                \
    0x0008 ///< This flag informs that the driver received data for entire frame defined in the \ref
    0x0008 ///< This flag informs that the driver received data for entire frame defined in the
           ///< EinkDataStartTransmissionWindow command
#define EINK_FLAG_I2C_BUSY           0x0010 ///< This flag informs that the I2C master periph is busy. Active low
#define EINK_FLAG_I2C_BUSY           0x0010 ///< This flag informs that the I2C master peripheral is busy. Active low
#define EINK_FLAG_I2C_ERROR          0x0020 ///< This flag informs that the I2C master acquired an error
#define EINK_FLAG_PIPELINE_COLLISION 0x0040 ///< This flag informs that two frames sent in the pipelin overlap
#define EINK_FLAG_PIPELINE_COLLISION 0x0040 ///< This flag informs that two frames sent in the pipeline overlap
#define EINK_FLAG_PIPELINE_BUSY      0x0080 ///< This flag informs that pipeline insertion is in progress
#define EINK_FLAG_REAGL_BUSY         0x0100 ///< This flag informs that the REAGLS function processing is in progress
#define EINK_FLAG_DITHER_IN_PROGRESS 0x0200 ///< This flag informs that the Dither process is in progress


@@ 234,137 217,143 @@ extern "C"
#define EINK_FLAG_BOOST_VOLTAGE_READY       0x4000 ///< This flag informs that the Boost voltage is ready
#define EINK_FLAG_RAM_TEST_FLAG             0x8000 ///< This flag is for internal SRAM memory testing

    /* Exported types ------------------------------------------------------------*/
    /**
     * @enum EinkStatus_e
     */
    typedef enum
// Booster configs
#define EPD_BOOSTER_START_PERIOD_10MS 0
#define EPD_BOOSTER_START_PERIOD_20MS 1
#define EPD_BOOSTER_START_PERIOD_30MS 2
#define EPD_BOOSTER_START_PERIOD_40MS 3
#define EPD_BOOSTER_START_PERIOD_POS  6

#define EPD_BOOSTER_DRIVING_STRENGTH_1   0
#define EPD_BOOSTER_DRIVING_STRENGTH_2   1
#define EPD_BOOSTER_DRIVING_STRENGTH_3   2
#define EPD_BOOSTER_DRIVING_STRENGTH_4   3
#define EPD_BOOSTER_DRIVING_STRENGTH_5   4
#define EPD_BOOSTER_DRIVING_STRENGTH_6   5
#define EPD_BOOSTER_DRIVING_STRENGTH_7   6
#define EPD_BOOSTER_DRIVING_STRENGTH_8   7
#define EPD_BOOSTER_DRIVING_STRENGTH_POS 3

#define EPD_BOOSTER_OFF_TIME_GDR_0_27uS 0
#define EPD_BOOSTER_OFF_TIME_GDR_0_34uS 1
#define EPD_BOOSTER_OFF_TIME_GDR_0_40uS 2
#define EPD_BOOSTER_OFF_TIME_GDR_0_54uS 3
#define EPD_BOOSTER_OFF_TIME_GDR_0_80uS 4
#define EPD_BOOSTER_OFF_TIME_GDR_1_54uS 5
#define EPD_BOOSTER_OFF_TIME_GDR_3_34uS 6
#define EPD_BOOSTER_OFF_TIME_GDR_6_58uS 7
#define EPD_BOOSTER_OFF_TIME_GDR_POS    0

#define EINK_IMAGE_CONFIG_SIZE 2 // 2 bytes at the beginning of each image frame
#define EINK_BITS_IN_BYTE      8
#define EINK_MAX_BPP           4

namespace bsp::eink
{
    enum class EinkStatus
    {
        EinkOK, //!< EinkOK
        EinkError,
        EinkSPIErr,                //!< EinkSPIErr
        EinkSPINotInitializedErr,  //!< EinkSPINotInitializedErr
        EinkDMAErr,                //!< EinkDMAErr
        EinkInitErr,               //!< EinkInitErr
        EinkTimeout,               //!< Timeout occured while waiting for not busy signal from EINK
        EinkNoMem,                 //!< Could not allocate memory
        EinkWaveformsFileOpenFail, //!< Could not open the file with the waveforms for EPD display
    } EinkStatus_e;

    /**
     * @enum EinkBpp_e
     */
    typedef enum
        OK,
        Error,
        SPIErr,
        SPINotInitializedErr,
        DMAErr,
        InitErr,
        Timeout,              //!< Timeout occured while waiting for not busy signal from EINK
        NoMem,                //!< Could not allocate memory
        WaveformsFileOpenFail //!< Could not open the file with the waveforms for EPD display
    };

    enum class EinkBpp
    {
        Eink1Bpp = 1, //!< Eink1Bpp
        Eink2Bpp,     //!< Eink2Bpp
        Eink3Bpp,     //!< Eink3Bpp
        Eink4Bpp      //!< Eink4Bpp
    } EinkBpp_e;
        Eink1Bpp = 1, //!< 1 bit per pixel
        Eink2Bpp,     //!< 2 bits per pixel
        Eink3Bpp,     //!< 3 bits per pixel
        Eink4Bpp      //!< 4 bits per pixel
    };

    typedef enum
    enum class EinkWaveform
    {
        EinkWaveformINIT,  ///< Clears deeply the display
        EinkWaveformA2,    ///< Fastest, direct update, no flashing. Severe ghosting effect
        EinkWaveformDU2,   ///< Fast, direct update, no flashing. Medium ghosting effect
        EinkWaveformGLD16, ///< Slow, little flashing. Light ghosting mode
        EinkWaveformGC16,  ///< Slow, strong flashing. Next to none ghosting
    } EinkWaveforms_e;

    typedef enum
        INIT,  ///< Clears deeply the display
        A2,    ///< Fastest, direct update, no flashing. Severe ghosting effect
        DU2,   ///< Fast, direct update, no flashing. Medium ghosting effect
        GLD16, ///< Slow, little flashing. Light ghosting mode
        GC16   ///< Slow, strong flashing. Next to none ghosting
    };

    enum class EinkDisplayColorFilling
    {
        EinkDisplayTimingsDeepCleanMode,
        EinkDisplayTimingsHighContrastMode,
        EinkDisplayTimingsFastRefreshMode
    } EinkDisplayTimingsMode_e;
        Black = 0x00,
        White = 0xFF
    };

    typedef enum
    enum class EinkDisplayColorMode
    {
        EinkDisplayColorBlack = 0,
        EinkDisplayColorWhite = 0xFF
    } EinkDisplayColorFilling_e;
        Standard,
        Inverted
    };

    typedef enum
    struct EinkWaveformSettings
    {
        EinkDisplayColorModeStandard,
        EinkDisplayColorModeInverted
    } EinkDisplayColorMode_e;

    typedef struct
        EinkWaveform mode;        // Type of eink's waveform
        std::int32_t temperature; // Temperature of surrounding
        std::uint32_t useCounter; // Counts usage of this waveform (display refreshes)
        std::uint8_t *LUTCData;   // Pointer to lookup table for LUTC
        std::uint32_t LUTCSize;   // Size of LUTC data
        std::uint8_t *LUTDData;   // Pointer to lookup table for LUTD
        std::uint32_t LUTDSize;   // Size of LUTD data
    };

    struct EinkFrame
    {
        // type of eink's waveform
        EinkWaveforms_e mode;
        // temperature of surrounding
        int32_t temperature;
        // counts usage of this waveform (display refreshes)
        uint32_t useCounter;
        // pointer to lookup table for lut c
        uint8_t *LUTCData;
        // sizeo of lutc data
        uint32_t LUTCSize;
        // pointer to lookup table for lut d
        uint8_t *LUTDData;
        // size of lutd data
        uint32_t LUTDSize;
    } EinkWaveformSettings_t;

    typedef struct
    {
        uint16_t pos_x;
        uint16_t pos_y;
        uint16_t width;
        uint16_t height;
    } EinkFrame_t;

    /* Exported constants --------------------------------------------------------*/

    /* Exported functions ------------------------------------------------------- */
        std::uint16_t posX;
        std::uint16_t posY;
        std::uint16_t width;
        std::uint16_t height;
    };

    /**
     * This function returns the state of the EPD siplay powe
     * @return 1 if is currently powered on, 0 otherwise
     * @brief This function returns the state of the EPD display power state
     * @return true if is currently powered on, false otherwise
     */
    bool EinkIsPoweredOn();
    bool isPoweredOn();

    /**
     * This function powers on the display. Needed for refreshing, measuring the temperature
     * @brief This function powers on the display. Needed for refreshing, measuring the temperature
     */
    EinkStatus_e EinkPowerOn();
    EinkStatus powerOn();

    /**
     * This functions powers off the display
     * @brief This functions powers off the display
     */
    EinkStatus_e EinkPowerOff();
    EinkStatus powerOff();

    /**
     * @brief This function is responsible for turning eink of and releasing all resources.
     */
    EinkStatus_e EinkPowerDown(void);
    EinkStatus powerDown();

    /**
     * This function measures the ambient temperature using the ED028TC1 display internal temperature sensor.
     * @brief This function measures the ambient temperature using the ED028TC1 display internal temperature sensor.
     * @note The display needs to be powered on
     *
     * @return Ambient temperature in the degrees of Celsius
     */
    int16_t EinkGetTemperatureInternal();
    std::int16_t getTemperatureInternal();

    /**
     * @brief This function resets the eink display and setups the initial configuration
     */
    EinkStatus_e EinkResetAndInitialize();
    EinkStatus resetAndInitialize();

    /**
     * TODO: Fill The doxy when got info what does it do
     * @return
     * @brief TODO: Fill The doxy when got info what does it do
     */
    EinkStatus_e EinkWaitTillPipelineBusy();
    EinkStatus waitTillPipelineBusy();

    /**
     * TODO: Fill The doxy when got info what does it do
     * @return
     * @brief TODO: Fill The doxy when got info what does it do
     */
    EinkStatus_e EinkDitherDisplay();
    EinkStatus ditherDisplay();

    /**
     * @brief This function sends the part of image from the given buffer to the internal memory of the display. It


@@ 372,23 361,12 @@ extern "C"
     * @param frame [in] - part of screen on which the image will be written
     * @param buffer [in] -  pointer to image encoded according to \ref bpp set in initialization
     * @param bpp [in] - The format of the \ref buffer (number of the bits per pixel)
     * @param invertColors[in] - true if colors of the image are to be inverted, false otherwise
     * @param invertColors [in] - true if colors of the image are to be inverted, false otherwise
     *
     * @return  EinkNoMem - Could not allocate the temporary buffer
     *          EinkOK - Part of image send successfully
     */
    EinkStatus_e EinkUpdateFrame(EinkFrame_t frame,
                                 const uint8_t *buffer,
                                 EinkBpp_e bpp,
                                 EinkDisplayColorMode_e invertColors);

    /**
     * @brief This function sets the waveform to the \ref EinkWaveformINIT to make the display clearing more deep and
     * sends the white background
     * @param temperature [in] - current ambient temperature
     * @return EinkOK
     */
    // EinkStatus_e EinkClearScreenDeep (int8_t temperature);
    EinkStatus updateFrame(EinkFrame frame, const std::uint8_t *buffer, EinkBpp bpp, EinkDisplayColorMode invertColors);

    /**
     * @brief This function just displays the color (black or white) on the entire display. Used to clear the display


@@ 396,19 374,16 @@ extern "C"
     * @param colorFill [in] - color which is used to fill the display
     * @return EinkOK
     */
    EinkStatus_e EinkFillScreenWithColor(EinkDisplayColorFilling_e colorFill);
    EinkStatus fillScreenWithColor(EinkDisplayColorFilling colorFill);

    /**
     * @brief Refresh window on the screen. E-paper display tends to loose contrast over time. To Keep the image sharp
     * refresh is needed.
     * @param frame - part of screen on which image will be written
     * @param refreshTimingsMode [in] - EinkDisplayTimingsDeepCleanMode - if image is to be cleared precisely
     *                                  EinkDisplayTimingsHighContrastMode - if image is displayed in the high contrast
     * mode EinkDisplayTimingsFastRefreshMode - if image is to be displayed fast
     * @param frame [in] - part of screen on which image will be written
     *
     * @return EinkOK
     */
    EinkStatus_e EinkRefreshImage(EinkFrame_t frame, EinkDisplayTimingsMode_e refreshTimingsMode);
    EinkStatus refreshImage(EinkFrame frame);

    /**
     * @brief This function sends the proper waveform consisting from the LUTC and LUTD data,


@@ 418,25 393,5 @@ extern "C"
     * @param LUTCData [in] - Data
     * @return
     */
    EinkStatus_e EinkUpdateWaveform(const EinkWaveformSettings_t *settings);

    /**
     * This function converts the ARGB image to the L4 format
     * @param dataIn  [in]  - input image
     * @param dataOut [out] - output image
     * @param displayWidth    [in] - display width in pixels
     * @param displayHeight   [in] - display height in pixels
     */
    void EinkARGBToLuminance(const uint8_t *dataIn, uint8_t *dataOut, uint32_t displayWidth, uint32_t displayHeight);

    /**
     * This function gets resolutions settings from EINK display
     */
    EinkStatus_e EinkGetResolutionSettings();
#if defined(__cplusplus)
}
#endif /* __cplusplus */

#endif /* __ED028TC1_H */

/******************* (C) COPYRIGHT 2017 mudita *****END OF FILE****/
    EinkStatus updateWaveform(const EinkWaveformSettings *settings);
} // namespace bsp::eink

R module-bsp/board/rt1051/bsp/eink/eink_binarization_luts.c => module-bsp/board/rt1051/bsp/eink/EinkBinarizationLuts.hpp +7 -7
@@ 1,9 1,11 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#include <stdint-gcc.h>
#pragma once

const uint8_t einkBinarizationLUT_2bpp[256] = {
#include <cstdint>

inline constexpr std::uint8_t einkBinarizationLUT2bpp[256] = {
    0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x03, 0x0c, 0x0c, 0x0c, 0x0f, 0x00, 0x00, 0x00,
    0x03, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x03, 0x0c, 0x0c, 0x0c, 0x0f, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
    0x00, 0x03, 0x00, 0x00, 0x00, 0x03, 0x0c, 0x0c, 0x0c, 0x0f, 0x30, 0x30, 0x30, 0x33, 0x30, 0x30, 0x30, 0x33, 0x30,


@@ 17,10 19,9 @@ const uint8_t einkBinarizationLUT_2bpp[256] = {
    0x3c, 0x3f, 0xc0, 0xc0, 0xc0, 0xc3, 0xc0, 0xc0, 0xc0, 0xc3, 0xc0, 0xc0, 0xc0, 0xc3, 0xcc, 0xcc, 0xcc, 0xcf, 0xc0,
    0xc0, 0xc0, 0xc3, 0xc0, 0xc0, 0xc0, 0xc3, 0xc0, 0xc0, 0xc0, 0xc3, 0xcc, 0xcc, 0xcc, 0xcf, 0xc0, 0xc0, 0xc0, 0xc3,
    0xc0, 0xc0, 0xc0, 0xc3, 0xc0, 0xc0, 0xc0, 0xc3, 0xcc, 0xcc, 0xcc, 0xcf, 0xf0, 0xf0, 0xf0, 0xf3, 0xf0, 0xf0, 0xf0,
    0xf3, 0xf0, 0xf0, 0xf0, 0xf3, 0xfc, 0xfc, 0xfc, 0xff,
};
    0xf3, 0xf0, 0xf0, 0xf0, 0xf3, 0xfc, 0xfc, 0xfc, 0xff};

const uint8_t einkBinarizationLUT_4bpp[256] = {
inline constexpr std::uint8_t einkBinarizationLUT4bpp[256] = {
    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00,
    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,


@@ 34,5 35,4 @@ const uint8_t einkBinarizationLUT_4bpp[256] = {
    0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00,
    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00,
    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0,
    0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xff,
};
    0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xff};

A module-bsp/board/rt1051/bsp/eink/EinkBufferTransformation.cpp => module-bsp/board/rt1051/bsp/eink/EinkBufferTransformation.cpp +324 -0
@@ 0,0 1,324 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "EinkBufferTransformation.hpp"
#include "EinkDimensions.hpp"
#include "EinkBinarizationLuts.hpp"
#include <cstdint>

namespace
{
    /**
     * @brief This LUT is used for conversion of the 4bpp input grayscale pixel to the 1bpp output pixel
     */
    constexpr std::uint8_t einkMaskLut1Bpp[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1};

    /**
     * @brief This LUT is used for conversion of the 4bpp input grayscale pixel to the 2bpp output pixel
     */
    constexpr std::uint8_t einkMaskLut2Bpp[16] = {0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3};
} // namespace

namespace bsp::eink
{
    __attribute__((optimize("O1"))) std::uint8_t *transformFrameCoordinateSystem1Bpp(const std::uint8_t *dataIn,
                                                                                     std::uint16_t windowWidthPx,
                                                                                     std::uint16_t windowHeightPx,
                                                                                     std::uint8_t *dataOut,
                                                                                     EinkDisplayColorMode invertColors)
    {
        // In 1bpp mode there are 8 pixels in the byte
        constexpr std::uint8_t pixelsInByte = 8;

        auto outArray = dataOut;

        for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
            for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
                // take considerable amount of time.
                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                // Use the LUT to convert the input pixel from 4bpp to 1bpp
                const auto firstPixel   = einkMaskLut1Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]];
                const auto secondPixel  = einkMaskLut1Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]];
                const auto thirdPixel   = einkMaskLut1Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]];
                const auto fourthPixel  = einkMaskLut1Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]];
                const auto fifthPixel   = einkMaskLut1Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]];
                const auto sixthPixel   = einkMaskLut1Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]];
                const auto seventhPixel = einkMaskLut1Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]];
                const auto eightPixel   = einkMaskLut1Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]];

                // Put the pixels in order: Most left positioned pixel at the most significant side of byte
                std::uint8_t pixels = (firstPixel << 7) | (secondPixel << 6) | (thirdPixel << 5) | (fourthPixel << 4) |
                                      (fifthPixel << 3) | (sixthPixel << 2) | (seventhPixel << 1) | (eightPixel << 0);

                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformFrameCoordinateSystem2Bpp(const std::uint8_t *dataIn,
                                                                                     std::uint16_t windowWidthPx,
                                                                                     std::uint16_t windowHeightPx,
                                                                                     std::uint8_t *dataOut,
                                                                                     EinkDisplayColorMode invertColors)
    {
        // In 2bpp mode there are 4 pixels in the byte
        constexpr std::uint8_t pixelsInByte = 4;

        auto outArray = reinterpret_cast<std::uint16_t *>(dataOut);

        for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
            for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
                // take considerable amount of time.
                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
                std::uint8_t temp = (einkMaskLut2Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]] << 6);
                temp |= (einkMaskLut2Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]] << 4);
                temp |= (einkMaskLut2Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]] << 2);
                temp |= (einkMaskLut2Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]] << 0);

                // Push the 4 pixels into the proper place in the uint16_t
                std::uint16_t pixels = (temp << 0);

                // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
                temp = (einkMaskLut2Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]] << 6);
                temp |= (einkMaskLut2Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]] << 4);
                temp |= (einkMaskLut2Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]] << 2);
                temp |= (einkMaskLut2Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]] << 0);

                // Push the 4 pixels into the proper place in the uint16_t
                pixels |= (temp << 8);

                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformFrameCoordinateSystem3Bpp(const std::uint8_t *dataIn,
                                                                                     std::uint16_t windowWidthPx,
                                                                                     std::uint16_t windowHeightPx,
                                                                                     std::uint8_t *dataOut,
                                                                                     EinkDisplayColorMode invertColors)
    {
        // The 4bpp is coded the same way as the 3bpp
        return transformFrameCoordinateSystem4Bpp(dataIn, windowWidthPx, windowHeightPx, dataOut, invertColors);
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformAnimationFrameCoordinateSystem1Bpp(
        const std::uint8_t *dataIn,
        std::uint16_t windowWidthPx,
        std::uint16_t windowHeightPx,
        std::uint8_t *dataOut,
        EinkDisplayColorMode invertColors)
    {
        // In 1bpp mode there are 8 pixels in the byte
        constexpr std::uint8_t pixelsInByte = 8;

        auto outArray = dataOut;

        for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
            for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of
                // data take considerable amount of time.

                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                // Use the LUT to convert the input pixel from 4bpp to 1bpp
                const auto firstPixel   = einkMaskLut1Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]];
                const auto secondPixel  = einkMaskLut1Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]];
                const auto thirdPixel   = einkMaskLut1Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]];
                const auto fourthPixel  = einkMaskLut1Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]];
                const auto fifthPixel   = einkMaskLut1Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]];
                const auto sixthPixel   = einkMaskLut1Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]];
                const auto seventhPixel = einkMaskLut1Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]];
                const auto eightPixel   = einkMaskLut1Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]];

                // Put the pixels in order: Most left positioned pixel at the most significant side of byte
                std::uint8_t pixels = (firstPixel << 7) | (secondPixel << 6) | (thirdPixel << 5) | (fourthPixel << 4) |
                                      (fifthPixel << 3) | (sixthPixel << 2) | (seventhPixel << 1) | (eightPixel << 0);

                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformAnimationFrameCoordinateSystem2Bpp(
        const std::uint8_t *dataIn,
        std::uint16_t windowWidthPx,
        std::uint16_t windowHeightPx,
        std::uint8_t *dataOut,
        EinkDisplayColorMode invertColors)
    {
        // In 2bpp mode there are 4 pixels in the byte
        constexpr std::uint8_t pixelsInByte = 4;

        auto outArray = reinterpret_cast<std::uint16_t *>(dataOut);

        for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
            for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
                // take considerable amount of time.
                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
                std::uint8_t temp = (einkMaskLut2Bpp[dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X]] << 6);
                temp |= (einkMaskLut2Bpp[dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X]] << 4);
                temp |= (einkMaskLut2Bpp[dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X]] << 2);
                temp |= (einkMaskLut2Bpp[dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X]] << 0);

                // Use the LUT to binarize the 2bpp pixels value and push them into the proper place in the uint16_t
                std::uint16_t pixels = einkBinarizationLUT2bpp[temp] << 0;

                // Use the LUT to convert the input pixel from 4bpp to 2bpp and put 4 pixels in single byte
                temp = (einkMaskLut2Bpp[dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X]] << 6);
                temp |= (einkMaskLut2Bpp[dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X]] << 4);
                temp |= (einkMaskLut2Bpp[dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X]] << 2);
                temp |= (einkMaskLut2Bpp[dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X]] << 0);

                // Use the LUT to binarize the 2bpp pixels value and push them into the proper place in the uint16_t
                pixels |= (einkBinarizationLUT2bpp[temp] << 8);
                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformAnimationFrameCoordinateSystem3Bpp(
        const std::uint8_t *dataIn,
        std::uint16_t windowWidthPx,
        std::uint16_t windowHeightPx,
        std::uint8_t *dataOut,
        EinkDisplayColorMode invertColors)
    {
        // The 4bpp is coded the same way as the 3bpp
        return transformFrameCoordinateSystem4Bpp(dataIn, windowWidthPx, windowHeightPx, dataOut, invertColors);
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformFrameCoordinateSystem4Bpp(const std::uint8_t *dataIn,
                                                                                     std::uint16_t windowWidthPx,
                                                                                     std::uint16_t windowHeightPx,
                                                                                     std::uint8_t *dataOut,
                                                                                     EinkDisplayColorMode invertColors)
    {
        // In 3bpp and 4bpp modes there are 2 pixels in the byte. Using 8bpp to process the whole uint32_t at once for
        // faster execution
        constexpr std::uint8_t pixelsInByte = 8;

        auto outArray = reinterpret_cast<std::uint32_t *>(dataOut);

        for (std::int32_t inputCol = windowWidthPx - 1; inputCol >= 0; --inputCol) {
            for (std::int32_t inputRow = windowHeightPx - 1; inputRow >= 7; inputRow -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
                // take considerable amount of time. Using 8 pixels at a time for better performance
                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                const auto firstPixelPair =
                    (dataIn[index - 0 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 1 * BOARD_EINK_DISPLAY_RES_X];
                const auto secondPixelPair =
                    (dataIn[index - 2 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 3 * BOARD_EINK_DISPLAY_RES_X];
                const auto thirdPixelPair =
                    (dataIn[index - 4 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 5 * BOARD_EINK_DISPLAY_RES_X];
                const auto fourthPixelPair =
                    (dataIn[index - 6 * BOARD_EINK_DISPLAY_RES_X] << 4) | dataIn[index - 7 * BOARD_EINK_DISPLAY_RES_X];

                // Put the pixels in the uint32_t for faster processing
                std::uint32_t pixels =
                    (firstPixelPair << 0) | (secondPixelPair << 8) | (thirdPixelPair << 16) | (fourthPixelPair << 24);

                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                // Put the pixels in order: Most left positioned pixel at the most significant side of byte
                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }

    __attribute__((optimize("O1"))) std::uint8_t *transformFrameCoordinateSystemNoRotation4Bpp(
        const std::uint8_t *dataIn,
        std::uint16_t windowWidthPx,
        std::uint16_t windowHeightPx,
        std::uint8_t *dataOut,
        EinkDisplayColorMode invertColors)
    {
        // In 3bpp and 4bpp modes there are 2 pixels in the byte. Using 8bpp to process the whole uint32_t at once for
        // faster execution
        const std::uint8_t pixelsInByte = 8;

        auto outArray = reinterpret_cast<std::uint32_t *>(dataOut);

        for (std::int32_t inputRow = 0; inputRow < windowHeightPx; ++inputRow) {
            for (std::int32_t inputCol = windowWidthPx - 7; inputCol >= 0; inputCol -= pixelsInByte) {
                // HACK: Did not create the loop for accessing pixels and merging them in the single byte for better
                // performance.
                // Wanted to avoid unneeded loop count increasing and jump operations which for large amount of data
                // take considerable amount of time. Using 8 pixels at a time for better performance
                const std::uint32_t index = inputRow * BOARD_EINK_DISPLAY_RES_X + inputCol;

                // Get 4x 2 adjacent pixels to process them as uint32_t for better execution timings
                const auto firstPixelPair  = (dataIn[index]) | (dataIn[index + 1] << 4);
                const auto secondPixelPair = (dataIn[index + 2]) | (dataIn[index + 3] << 4);
                const auto thirdPixelPair  = (dataIn[index + 4]) | (dataIn[index + 5] << 4);
                const auto fourthPixelPair = (dataIn[index + 6]) | (dataIn[index + 7] << 4);

                // Put the pixels in the uint32_t for faster processing
                std::uint32_t pixels =
                    (firstPixelPair << 24) | (secondPixelPair << 16) | (thirdPixelPair << 8) | (fourthPixelPair);

                if (invertColors == EinkDisplayColorMode::Inverted) {
                    pixels = ~pixels;
                }

                // Put the pixels in order: Most left positioned pixel at the most significant side of byte
                *outArray = pixels;
                ++outArray;
            }
        }

        return dataOut;
    }
} // namespace bsp::eink

A module-bsp/board/rt1051/bsp/eink/EinkBufferTransformation.hpp => module-bsp/board/rt1051/bsp/eink/EinkBufferTransformation.hpp +407 -0
@@ 0,0 1,407 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#pragma once

#include "ED028TC1.hpp"
#include <cstdint>

namespace bsp::eink
{
    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 1Bpp image
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent a
     *  single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformFrameCoordinateSystem1Bpp(const std::uint8_t *dataIn,
                                                     std::uint16_t windowWidthPx,
                                                     std::uint16_t windowHeightPx,
                                                     std::uint8_t *dataOut,
                                                     EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 2Bpp image
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformFrameCoordinateSystem2Bpp(const std::uint8_t *dataIn,
                                                     std::uint16_t windowWidthPx,
                                                     std::uint16_t windowHeightPx,
                                                     std::uint8_t *dataOut,
                                                     EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 3Bpp image
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformFrameCoordinateSystem3Bpp(const std::uint8_t *dataIn,
                                                     std::uint16_t windowWidthPx,
                                                     std::uint16_t windowHeightPx,
                                                     std::uint8_t *dataOut,
                                                     EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 4Bpp image
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformFrameCoordinateSystem4Bpp(const std::uint8_t *dataIn,
                                                     std::uint16_t windowWidthPx,
                                                     std::uint16_t windowHeightPx,
                                                     std::uint8_t *dataOut,
                                                     EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 1Bpp image. It also makes sure that the image is black and white only
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformAnimationFrameCoordinateSystem1Bpp(const std::uint8_t *dataIn,
                                                              std::uint16_t windowWidthPx,
                                                              std::uint16_t windowHeightPx,
                                                              std::uint8_t *dataOut,
                                                              EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 2Bpp image. It also makes sure that the image is black and white only
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformAnimationFrameCoordinateSystem2Bpp(const std::uint8_t *dataIn,
                                                              std::uint16_t windowWidthPx,
                                                              std::uint16_t windowHeightPx,
                                                              std::uint8_t *dataOut,
                                                              EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 3Bpp image. It also makes sure that the image is black and white only
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */
    std::uint8_t *transformAnimationFrameCoordinateSystem3Bpp(const std::uint8_t *dataIn,
                                                              std::uint16_t windowWidthPx,
                                                              std::uint16_t windowHeightPx,
                                                              std::uint8_t *dataOut,
                                                              EinkDisplayColorMode invertColors);

    /**
     *  This function makes rotation of the image from the standard GUI coordinate system to the coord system used by
     * the ED028TC1 display.
     *
     *  @note IT ROTATES only the 4Bpp image. It also makes sure that the image is black and white only
     *
     *  @param uint8_t* dataIn          [in]  - input image to be translated. Each byte of that array must represent the
     * single pixel
     *  @param uint16_t x               [in]  - x coordinate of image in pixels
     *  @param uint16_t y               [in]  - y coordinate of image in pixels
     *  @param uint16_t windowWidthPx   [in]  - width of the image in pixels
     *  @param uint16_t windowHeightPx  [in]  - height of the image in pixels
     *  @param uint8_t* dataOut         [out] - the buffer for rotated image
     *  @param invertColors [in] - Inverted if colors of the image are to be inverted, Standard otherwise
     *
     * @note Assumed dataIn coordinate system is the standard image coordinates system:
     *
     *   (0,0)   X
     *       *-------->
     *       |
     *     Y |
     *       |
     *       v
     *
     *
     * The result of the function is such a conversion of the dataIn array to make the Eink display show it the very
     * same way in its own coordinate system which is:
     *
     *              displayWidth
     *                 _______  ^
     *                |       | |
     *                |       | |
     *  displayHeight |       | |
     *                |       | |
     *                |_______| |  X
     *                   \ /    |
     *    signal tape -  | |    |
     *                          |
     *                 <--------*
     *                    Y     (0,0)
     *
     * @return
     */

    /*
     * Non-rotating version of s_EinkTransformAnimationFrameCoordinateSystem_4Bpp.
     * It is used when EINK_ROTATE_90_CLOCKWISE is not defined.
     */
    std::uint8_t *transformFrameCoordinateSystemNoRotation4Bpp(const std::uint8_t *dataIn,
                                                               std::uint16_t windowWidthPx,
                                                               std::uint16_t windowHeightPx,
                                                               std::uint8_t *dataOut,
                                                               EinkDisplayColorMode invertColors);
} // namespace bsp::eink

R module-bsp/board/rt1051/bsp/eink/eink_dimensions.cpp => module-bsp/board/rt1051/bsp/eink/EinkDimensions.cpp +12 -15
@@ 1,32 1,30 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#include "eink_dimensions.hpp"
// For licensing, see https://github.com/mudita/MuditaOS/LICENSE.md

#include "EinkDimensions.hpp"
#include <eink-config.h>

namespace hal::eink
namespace bsp::eink
{

    std::uint32_t getDisplayXAxis(EinkFrame_t frame)
    std::uint32_t getDisplayXAxis(EinkFrame frame)
    {
#if defined(EINK_ROTATE_90_CLOCKWISE)
        return BOARD_EINK_DISPLAY_RES_Y - frame.pos_y - frame.height;
        return BOARD_EINK_DISPLAY_RES_Y - frame.posY - frame.height;
#else
        return BOARD_EINK_DISPLAY_RES_X - frame.pos_x - frame.width;
        return BOARD_EINK_DISPLAY_RES_X - frame.posX - frame.width;
#endif
    }

    std::uint32_t getDisplayYAxis(EinkFrame_t frame)
    std::uint32_t getDisplayYAxis(EinkFrame frame)
    {
#if defined(EINK_ROTATE_90_CLOCKWISE)
        return BOARD_EINK_DISPLAY_RES_X - frame.pos_x - frame.width;
        return BOARD_EINK_DISPLAY_RES_X - frame.posX - frame.width;
#else
        return frame.pos_y;
        return frame.posY;
#endif
    }

    std::uint32_t getDisplayWindowWidth(EinkFrame_t frame)
    std::uint32_t getDisplayWindowWidth(EinkFrame frame)
    {
#if defined(EINK_ROTATE_90_CLOCKWISE)
        return frame.height;


@@ 35,7 33,7 @@ namespace hal::eink
#endif
    }

    std::uint32_t getDisplayWindowHeight(EinkFrame_t frame)
    std::uint32_t getDisplayWindowHeight(EinkFrame frame)
    {
#if defined(EINK_ROTATE_90_CLOCKWISE)
        return frame.width;


@@ 43,5 41,4 @@ namespace hal::eink
        return frame.height;
#endif
    }

} // namespace hal::eink
} // namespace bsp::eink

R module-bsp/board/rt1051/bsp/eink/eink_dimensions.hpp => module-bsp/board/rt1051/bsp/eink/EinkDimensions.hpp +7 -7
@@ 6,7 6,7 @@
#include <cstdint>

#include <eink-config.h>
#include "ED028TC1.h"
#include "ED028TC1.hpp"

#if defined(EINK_ROTATE_90_CLOCKWISE)
#define EINK_DISPLAY_RES_X (BOARD_EINK_DISPLAY_RES_Y)


@@ 16,10 16,10 @@
#define EINK_DISPLAY_RES_Y (BOARD_EINK_DISPLAY_RES_Y)
#endif

namespace hal::eink
namespace bsp::eink
{
    std::uint32_t getDisplayXAxis(EinkFrame_t frame);
    std::uint32_t getDisplayYAxis(EinkFrame_t frame);
    std::uint32_t getDisplayWindowWidth(EinkFrame_t frame);
    std::uint32_t getDisplayWindowHeight(EinkFrame_t frame);
} // namespace hal::eink
    std::uint32_t getDisplayXAxis(EinkFrame frame);
    std::uint32_t getDisplayYAxis(EinkFrame frame);
    std::uint32_t getDisplayWindowWidth(EinkFrame frame);
    std::uint32_t getDisplayWindowHeight(EinkFrame frame);
} // namespace bsp::eink

M module-bsp/board/rt1051/bsp/eink/EinkDisplay.cpp => module-bsp/board/rt1051/bsp/eink/EinkDisplay.cpp +128 -128
@@ 17,7 17,7 @@ namespace hal::eink
{
    namespace
    {
        constexpr auto DefaultSurroundingTemperature = -1000;
        constexpr auto defaultSurroundingTemperature = -1000;
        constexpr auto LUTDSize                      = 16385;
        constexpr auto LUTCSize                      = 64;
        constexpr auto LUTRSize                      = 256; ///< Needed due to \ref LutsFileName structure


@@ 30,15 30,16 @@ namespace hal::eink
        constexpr auto LUTTemperatureOffsetInterval    = 3;
        constexpr auto LUTTemperatureOffsetSubcritical = 12;
        constexpr auto LUTTemperatureOffsetCritical    = 13;
        constexpr auto EinkDisplayMaxInitRetries       = 10U;
        constexpr auto einkDisplayMaxInitRetries       = 10U;

        const auto LutsFilePath = purefs::dir::getAssetsDirPath() / "luts.bin";
        const auto lutsFilePath = purefs::dir::getAssetsDirPath() / "luts.bin";

        EinkWaveformSettings_t createDefaultWaveFormSettings(EinkWaveforms_e waveformMode)
        constexpr auto createDefaultWaveformSettings(bsp::eink::EinkWaveform waveformMode)
            -> bsp::eink::EinkWaveformSettings
        {
            EinkWaveformSettings_t settings{};
            bsp::eink::EinkWaveformSettings settings{};
            settings.mode        = waveformMode;
            settings.temperature = DefaultSurroundingTemperature;
            settings.temperature = defaultSurroundingTemperature;
            settings.useCounter  = 0;
            settings.LUTCData    = nullptr;
            settings.LUTCSize    = 0;


@@ 47,7 48,7 @@ namespace hal::eink
            return settings;
        }

        unsigned int toWaveformTemperatureOffset(std::int32_t temperature) noexcept
        constexpr auto toWaveformTemperatureOffset(std::int32_t temperature) noexcept -> unsigned
        {
            if (temperature >= LUTTemperatureCritical) {
                return LUTTemperatureOffsetCritical;


@@ 61,67 62,67 @@ namespace hal::eink
            return temperature / LUTTemperatureOffsetInterval;
        }

        unsigned int toWaveformOffset(unsigned short LUTbank, unsigned int temperatureOffset) noexcept
        constexpr auto toWaveformOffset(unsigned short LUTbank, unsigned temperatureOffset) noexcept -> unsigned
        {
            constexpr auto singleLUTOffset = (LUTTemperatureOffsetCritical + 1);
            return LUTSTotalSize * (singleLUTOffset * LUTbank + temperatureOffset);
        }

        unsigned int toWaveformOffset(EinkWaveforms_e mode, unsigned int temperatureOffset)
        constexpr auto toWaveformOffset(bsp::eink::EinkWaveform mode, unsigned temperatureOffset) -> unsigned
        {
            switch (mode) {
            case EinkWaveformINIT:
            case bsp::eink::EinkWaveform::INIT:
                return toWaveformOffset(0, temperatureOffset);
            case EinkWaveformA2:
            case bsp::eink::EinkWaveform::A2:
                return toWaveformOffset(1, temperatureOffset);
            case EinkWaveformDU2:
            case bsp::eink::EinkWaveform::DU2:
                return toWaveformOffset(2, temperatureOffset);
            case EinkWaveformGLD16:
            case bsp::eink::EinkWaveform::GLD16:
                return toWaveformOffset(3, temperatureOffset);
            case EinkWaveformGC16:
            case bsp::eink::EinkWaveform::GC16:
                return toWaveformOffset(4, temperatureOffset);
            default:
                throw std::invalid_argument{"Invalid waveform mode."};
            }
        }
    } // namespace

    EinkDisplayColorMode_e translateDisplayColorMode(const EinkDisplayColorMode mode)
    {
        return mode == EinkDisplayColorMode::EinkDisplayColorModeStandard
                   ? EinkDisplayColorMode_e::EinkDisplayColorModeStandard
                   : EinkDisplayColorMode_e::EinkDisplayColorModeInverted;
    }
        constexpr auto translateDisplayColorMode(EinkDisplayColorMode mode) -> bsp::eink::EinkDisplayColorMode
        {
            return mode == EinkDisplayColorMode::EinkDisplayColorModeStandard
                       ? bsp::eink::EinkDisplayColorMode::Standard
                       : bsp::eink::EinkDisplayColorMode::Inverted;
        }

    EinkStatus translateStatus(const EinkStatus_e status_e)
    {
        switch (status_e) {
        case EinkOK:
            return EinkStatus::EinkOK;
        case EinkError:
            return EinkStatus::EinkError;
        case EinkSPIErr:
            return EinkStatus::EinkSPIErr;
        case EinkSPINotInitializedErr:
            return EinkStatus::EinkSPINotInitializedErr;
        case EinkDMAErr:
            return EinkStatus::EinkDMAErr;
        case EinkInitErr:
            return EinkStatus::EinkInitErr;
        case EinkTimeout:
            return EinkStatus::EinkTimeout;
        case EinkNoMem:
            return EinkStatus::EinkNoMem;
        case EinkWaveformsFileOpenFail:
            return EinkStatus::EinkWaveformsFileOpenFail;
        default:
            return EinkStatus::EinkUnknown;
        constexpr auto translateStatus(bsp::eink::EinkStatus status) -> EinkStatus
        {
            switch (status) {
            case bsp::eink::EinkStatus::OK:
                return EinkStatus::EinkOK;
            case bsp::eink::EinkStatus::Error:
                return EinkStatus::EinkError;
            case bsp::eink::EinkStatus::SPIErr:
                return EinkStatus::EinkSPIErr;
            case bsp::eink::EinkStatus::SPINotInitializedErr:
                return EinkStatus::EinkSPINotInitializedErr;
            case bsp::eink::EinkStatus::DMAErr:
                return EinkStatus::EinkDMAErr;
            case bsp::eink::EinkStatus::InitErr:
                return EinkStatus::EinkInitErr;
            case bsp::eink::EinkStatus::Timeout:
                return EinkStatus::EinkTimeout;
            case bsp::eink::EinkStatus::NoMem:
                return EinkStatus::EinkNoMem;
            case bsp::eink::EinkStatus::WaveformsFileOpenFail:
                return EinkStatus::EinkWaveformsFileOpenFail;
            default:
                return EinkStatus::EinkUnknown;
            }
        }
    }
    } // namespace

    EinkDisplay::EinkDisplay(FrameSize size)
        : size{size}, currentWaveform{createDefaultWaveFormSettings(EinkWaveformGC16)},
          displayMode{EinkDisplayColorMode_e::EinkDisplayColorModeStandard}
        : size{size}, currentWaveform{createDefaultWaveformSettings(bsp::eink::EinkWaveform::GC16)},
          displayMode{EinkDisplayColorMode::EinkDisplayColorModeStandard}
    {
#if defined(TARGET_RT1051)
        driverLPSPI = drivers::DriverLPSPI::Create(


@@ 135,17 136,17 @@ namespace hal::eink
        delete[] currentWaveform.LUTDData;
    }

    EinkStatus EinkDisplay::prepareDisplay(const EinkRefreshMode refreshMode, const WaveformTemperature behaviour)
    auto EinkDisplay::prepareDisplay(EinkRefreshMode refreshMode, WaveformTemperature behaviour) -> EinkStatus
    {
        if (const auto status = reinitAndPowerOn(); status != EinkStatus::EinkOK) {
            return status;
        }

        const auto temperature =
            behaviour == WaveformTemperature::KEEP_CURRENT ? getLastTemperature() : EinkGetTemperatureInternal();
        const auto temperature = (behaviour == WaveformTemperature::KeepCurrent) ? getLastTemperature()
                                                                                 : bsp::eink::getTemperatureInternal();

        if (refreshMode == EinkRefreshMode::REFRESH_DEEP) {
            auto status = setWaveform(EinkWaveforms_e::EinkWaveformGC16, temperature);
            auto status = setWaveform(bsp::eink::EinkWaveform::GC16, temperature);
            if (status == EinkStatus::EinkOK) {
                if (const auto ditherStatus = dither(); ditherStatus != EinkStatus::EinkOK) {
                    return ditherStatus;


@@ 153,30 154,27 @@ namespace hal::eink
            }
            return status;
        }
        return setWaveform(EinkWaveforms_e::EinkWaveformDU2, temperature);
        return setWaveform(bsp::eink::EinkWaveform::DU2, temperature);
    }

    EinkStatus EinkDisplay::updateDisplay(EinkFrame frame, const std::uint8_t *frameBuffer)
    auto EinkDisplay::updateDisplay(EinkFrame frame, const std::uint8_t *frameBuffer) -> EinkStatus
    {
        return translateStatus(
            EinkUpdateFrame(EinkFrame_t{frame.pos_x, frame.pos_y, frame.size.width, frame.size.height},
                            frameBuffer,
                            getCurrentBitsPerPixelFormat(),
                            translateDisplayColorMode(displayMode)));
            updateFrame(bsp::eink::EinkFrame{frame.pos_x, frame.pos_y, frame.size.width, frame.size.height},
                        frameBuffer,
                        getCurrentBitsPerPixelFormat(),
                        translateDisplayColorMode(displayMode)));
    }

    EinkStatus EinkDisplay::refreshDisplay(EinkFrame frame, const EinkRefreshMode refreshMode)
    auto EinkDisplay::refreshDisplay(EinkFrame frame) -> EinkStatus
    {
        const auto refreshTimingsMode = refreshMode == EinkRefreshMode::REFRESH_DEEP
                                            ? EinkDisplayTimingsDeepCleanMode
                                            : EinkDisplayTimingsFastRefreshMode;

        currentWaveform.useCounter += 1;
        return translateStatus(EinkRefreshImage(
            EinkFrame_t{frame.pos_x, frame.pos_y, frame.size.width, frame.size.height}, refreshTimingsMode));
        currentWaveform.useCounter++;
        return translateStatus(bsp::eink::refreshImage(
            bsp::eink::EinkFrame{frame.pos_x, frame.pos_y, frame.size.width, frame.size.height}));
    }

    EinkStatus EinkDisplay::showImageUpdate(const std::vector<EinkFrame> &updateFrames, const std::uint8_t *frameBuffer)
    auto EinkDisplay::showImageUpdate(const std::vector<EinkFrame> &updateFrames, const std::uint8_t *frameBuffer)
        -> EinkStatus
    {
        if (const auto status = reinitAndPowerOn(); status != EinkStatus::EinkOK) {
            return status;


@@ 192,26 190,26 @@ namespace hal::eink
        return EinkStatus::EinkOK;
    }

    EinkStatus EinkDisplay::showImageRefresh(const EinkFrame &refreshFrame, const EinkRefreshMode refreshMode)
    auto EinkDisplay::showImageRefresh(const EinkFrame &refreshFrame, const EinkRefreshMode refreshMode) -> EinkStatus
    {
        if (const auto status = prepareDisplay(refreshMode, WaveformTemperature::KEEP_CURRENT);
        if (const auto status = prepareDisplay(refreshMode, WaveformTemperature::KeepCurrent);
            status != EinkStatus::EinkOK) {
            return status;
        }

        if (const auto status = refreshDisplay(refreshFrame, refreshMode); status != EinkStatus::EinkOK) {
        if (const auto status = refreshDisplay(refreshFrame); status != EinkStatus::EinkOK) {
            return status;
        }

        return EinkStatus::EinkOK;
    }

    EinkStatus EinkDisplay::showImage(const std::vector<EinkFrame> &updateFrames,
                                      const EinkFrame &refreshFrame,
                                      const std::uint8_t *frameBuffer,
                                      const EinkRefreshMode refreshMode)
    auto EinkDisplay::showImage(const std::vector<EinkFrame> &updateFrames,
                                const EinkFrame &refreshFrame,
                                const std::uint8_t *frameBuffer,
                                const EinkRefreshMode refreshMode) -> EinkStatus
    {
        if (const auto status = prepareDisplay(refreshMode, WaveformTemperature::KEEP_CURRENT);
        if (const auto status = prepareDisplay(refreshMode, WaveformTemperature::KeepCurrent);
            status != EinkStatus::EinkOK) {
            return status;
        }


@@ 223,88 221,91 @@ namespace hal::eink
            }
        }

        if (const auto status = refreshDisplay(refreshFrame, refreshMode); status != EinkStatus::EinkOK) {
        if (const auto status = refreshDisplay(refreshFrame); status != EinkStatus::EinkOK) {
            return status;
        }

        return EinkStatus::EinkOK;
    }

    void EinkDisplay::prepareEarlyRequest(const EinkRefreshMode refreshMode, const WaveformTemperature behaviour)
    auto EinkDisplay::prepareEarlyRequest(const EinkRefreshMode refreshMode, const WaveformTemperature behaviour)
        -> void
    {
        prepareDisplay(refreshMode, behaviour);
    }

    EinkStatus EinkDisplay::resetAndInit()
    auto EinkDisplay::resetAndInit() -> EinkStatus
    {
        return translateStatus(EinkResetAndInitialize());
        return translateStatus(bsp::eink::resetAndInitialize());
    }

    EinkStatus EinkDisplay::dither()
    auto EinkDisplay::dither() -> EinkStatus
    {
        return translateStatus(EinkDitherDisplay());
        return translateStatus(bsp::eink::ditherDisplay());
    }

    EinkStatus EinkDisplay::powerOn()
    auto EinkDisplay::powerOn() -> EinkStatus
    {
        if (driverLPSPI) {
            driverLPSPI->Enable();
        }
        return translateStatus(EinkPowerOn());
        return translateStatus(bsp::eink::powerOn());
    }

    EinkStatus EinkDisplay::powerOff()
    auto EinkDisplay::powerOff() -> EinkStatus
    {
        const auto status = translateStatus(EinkPowerOff());
        const auto status = translateStatus(bsp::eink::powerOff());
        if (driverLPSPI) {
            driverLPSPI->Disable();
        }
        return status;
    }

    EinkStatus EinkDisplay::shutdown()
    auto EinkDisplay::shutdown() -> EinkStatus
    {
        const auto status = translateStatus(EinkPowerDown());
        const auto status = translateStatus(bsp::eink::powerDown());
        if (driverLPSPI) {
            driverLPSPI->Disable();
        }
        return status;
    }

    EinkStatus EinkDisplay::wipeOut()
    auto EinkDisplay::wipeOut() -> EinkStatus
    {
        if (const auto status = prepareDisplay(EinkRefreshMode::REFRESH_DEEP, WaveformTemperature::KEEP_CURRENT);
        if (const auto status = prepareDisplay(EinkRefreshMode::REFRESH_DEEP, WaveformTemperature::KeepCurrent);
            status != EinkStatus::EinkOK) {
            return status;
        }
        return translateStatus(EinkFillScreenWithColor(EinkDisplayColorFilling_e::EinkDisplayColorWhite));
        return translateStatus(bsp::eink::fillScreenWithColor(bsp::eink::EinkDisplayColorFilling::White));
    }

    EinkBpp_e EinkDisplay::getCurrentBitsPerPixelFormat() const noexcept
    auto EinkDisplay::getCurrentBitsPerPixelFormat() const noexcept -> bsp::eink::EinkBpp
    {
        if ((currentWaveform.mode == EinkWaveformA2) || (currentWaveform.mode == EinkWaveformDU2)) {
            return Eink4Bpp; // this should be 1Bpp, but the OS is not ready for this (in 1Bpp → halftones disappear)
        if ((currentWaveform.mode == bsp::eink::EinkWaveform::A2) ||
            (currentWaveform.mode == bsp::eink::EinkWaveform::DU2)) {
            /* Should be 1Bpp, but the OS is not ready for this and probably never will (in 1Bpp halftones disappear) */
            return bsp::eink::EinkBpp::Eink4Bpp;
        }
        return Eink4Bpp;
        return bsp::eink::EinkBpp::Eink4Bpp;
    }

    bool EinkDisplay::isNewWaveformNeeded(const EinkWaveforms_e newMode, const std::int32_t newTemperature) const
    auto EinkDisplay::isNewWaveformNeeded(bsp::eink::EinkWaveform newMode, std::int32_t newTemperature) const -> bool
    {
        constexpr auto lenientTemperatureUseCounter = 50; // arbitrary. not documented
        auto alloweLenientTemperature               = currentWaveform.useCounter < lenientTemperatureUseCounter;
        constexpr auto lenientTemperatureUseCounter = 50; // Arbitrary, not documented
        const auto allowLenientTemperature          = currentWaveform.useCounter < lenientTemperatureUseCounter;

        // at least: modes cannot differ
        if (alloweLenientTemperature && newMode == currentWaveform.mode) {
        // At least: modes cannot differ
        if (allowLenientTemperature && newMode == currentWaveform.mode) {
            bool temperatureFine = false;

            switch (currentWaveform.mode) {
            case EinkWaveformA2:
            case EinkWaveformDU2:
            case bsp::eink::EinkWaveform::A2:
            case bsp::eink::EinkWaveform::DU2:
                temperatureFine = abs(newTemperature - currentWaveform.temperature) <= 3;
                break;
            case EinkWaveformINIT:
            case EinkWaveformGLD16:
            case EinkWaveformGC16:
            case bsp::eink::EinkWaveform::INIT:
            case bsp::eink::EinkWaveform::GLD16:
            case bsp::eink::EinkWaveform::GC16:
                temperatureFine = abs(newTemperature - currentWaveform.temperature) <= 2;
                break;
            }


@@ 316,30 317,31 @@ namespace hal::eink
        return true;
    }

    EinkStatus EinkDisplay::setWaveform(const EinkWaveforms_e mode, const std::int32_t temperature)
    auto EinkDisplay::setWaveform(bsp::eink::EinkWaveform mode, std::int32_t temperature) -> EinkStatus
    {
        if (!isNewWaveformNeeded(mode, temperature)) {
            EinkUpdateWaveform(&currentWaveform);
            updateWaveform(&currentWaveform);
            return EinkStatus::EinkOK;
        }

        auto currentOffset =
        const auto currentOffset =
            toWaveformOffset(currentWaveform.mode, toWaveformTemperatureOffset(currentWaveform.temperature));
        // assume it is changed

        // Assume it's changed
        currentWaveform.useCounter  = 0;
        currentWaveform.temperature = temperature;
        currentWaveform.mode        = mode;

        auto offset = toWaveformOffset(mode, toWaveformTemperatureOffset(temperature));
        auto offset = static_cast<long>(toWaveformOffset(mode, toWaveformTemperatureOffset(temperature)));

        if (offset == currentOffset) {
            // current waveform is still the best fit
            // Current waveform is still the best fit
            return EinkStatus::EinkOK;
        }

        auto file = std::fopen(LutsFilePath.c_str(), "rb");
        auto file = std::fopen(lutsFilePath.c_str(), "rb");
        if (file == nullptr) {
            LOG_FATAL("Could not find LUTS file in '%s'! Returning...", LutsFilePath.c_str());
            LOG_FATAL("Could not find LUTS file in '%s'! Returning...", lutsFilePath.c_str());
            return EinkStatus::EinkWaveformsFileOpenFail;
        }
        auto fileHandlerCleanup = gsl::finally([&file]() { std::fclose(file); });


@@ 349,7 351,7 @@ namespace hal::eink
        std::fread(&currentWaveform.LUTDData[1], 1, LUTDSize, file);

        // 0x00 - 1 frame, ... , 0x0F - 16 frames
        const uint8_t waveformFrameCount = currentWaveform.LUTDData[1] + 1;
        const std::uint8_t waveformFrameCount = currentWaveform.LUTDData[1] + 1;
        // (frameCount * 64) - size of actual LUT; (+1) - the byte containing frameCount; (+1) - EinkLUTD command
        currentWaveform.LUTDSize = (waveformFrameCount * 64) + 1 + 1;



@@ 357,11 359,11 @@ namespace hal::eink
        std::fseek(file, offset, SEEK_SET);
        std::fread(&currentWaveform.LUTCData[1], 1, LUTCSize, file);

        EinkUpdateWaveform(&currentWaveform);
        updateWaveform(&currentWaveform);
        return EinkStatus::EinkOK;
    }

    void EinkDisplay::resetWaveformSettings()
    auto EinkDisplay::resetWaveformSettings() -> void
    {
        delete[] currentWaveform.LUTDData;
        currentWaveform.LUTDSize    = 0;


@@ 374,42 376,42 @@ namespace hal::eink
        currentWaveform.LUTCData[0] = EinkLUTC;
    }

    void EinkDisplay::setMode(const EinkDisplayColorMode mode) noexcept
    auto EinkDisplay::setMode(EinkDisplayColorMode mode) noexcept -> void
    {
        displayMode = mode;
    }

    EinkDisplayColorMode EinkDisplay::getMode() const noexcept
    auto EinkDisplay::getMode() const noexcept -> EinkDisplayColorMode
    {
        return displayMode;
    }

    std::int32_t EinkDisplay::getLastTemperature() const noexcept
    auto EinkDisplay::getLastTemperature() const noexcept -> std::int32_t
    {
        return currentWaveform.temperature;
    }

    [[nodiscard]] auto EinkDisplay::getDevice() const noexcept -> std::shared_ptr<devices::Device>
    auto EinkDisplay::getDevice() const noexcept -> std::shared_ptr<devices::Device>
    {
        return driverLPSPI;
    }

    std::unique_ptr<AbstractEinkDisplay> AbstractEinkDisplay::Factory::create(FrameSize size)
    auto AbstractEinkDisplay::Factory::create(FrameSize size) -> std::unique_ptr<AbstractEinkDisplay>
    {
        return std::make_unique<EinkDisplay>(size);
    }

    EinkStatus EinkDisplay::reinitAndPowerOn()
    auto EinkDisplay::reinitAndPowerOn() -> EinkStatus
    {
        auto errorCounter = 0U;
        auto status       = EinkStatus::EinkUnknown;
        if (EinkIsPoweredOn()) {
        if (bsp::eink::isPoweredOn()) {
            return EinkStatus::EinkOK;
        }
        while (status != EinkStatus::EinkOK && errorCounter++ < EinkDisplayMaxInitRetries) {
        while (status != EinkStatus::EinkOK && errorCounter++ < einkDisplayMaxInitRetries) {
            status = tryReinitAndPowerOn();
            if (status != EinkStatus::EinkOK) {
                if (errorCounter < EinkDisplayMaxInitRetries) {
                if (errorCounter < einkDisplayMaxInitRetries) {
                    LOG_WARN("Failed to initialize and power on Eink, trying once more...");
                }
                else {


@@ 417,21 419,19 @@ namespace hal::eink
                }
            }
        }

        return status;
    }

    EinkStatus EinkDisplay::tryReinitAndPowerOn()
    auto EinkDisplay::tryReinitAndPowerOn() -> EinkStatus
    {
        if (const auto status = resetAndInit(); status != EinkStatus::EinkOK) {
            LOG_WARN("Eink initialization failed (%s)", magic_enum::enum_name(status).data());
            LOG_WARN("Eink initialization failed: %s", magic_enum::enum_name(status).data());
            return status;
        }
        if (const auto status = powerOn(); status != EinkStatus::EinkOK) {
            LOG_WARN("Eink power on failed (%s)", magic_enum::enum_name(status).data());
            LOG_WARN("Eink power on failed: %s", magic_enum::enum_name(status).data());
            return status;
        }
        return EinkStatus::EinkOK;
    }

} // namespace hal::eink

M module-bsp/board/rt1051/bsp/eink/EinkDisplay.hpp => module-bsp/board/rt1051/bsp/eink/EinkDisplay.hpp +38 -38
@@ 3,13 3,13 @@

#pragma once

#include <cstdint>
#include <memory>
#include "drivers/lpspi/DriverLPSPI.hpp"
#include "ED028TC1.hpp"

#include <hal/eink/AbstractEinkDisplay.hpp>

#include "drivers/lpspi/DriverLPSPI.hpp"
#include "ED028TC1.h"
#include <cstdint>
#include <memory>

namespace hal::eink
{


@@ 21,50 21,50 @@ namespace hal::eink
    class EinkDisplay : public AbstractEinkDisplay
    {
      public:
        EinkDisplay(FrameSize size);

        ~EinkDisplay() noexcept;

        void setMode(EinkDisplayColorMode mode) noexcept override;
        EinkDisplayColorMode getMode() const noexcept override;

        EinkStatus showImageUpdate(const std::vector<EinkFrame> &updateFrames,
                                   const std::uint8_t *frameBuffer) override;
        EinkStatus showImageRefresh(const EinkFrame &refreshFrame, const EinkRefreshMode refreshMode) override;
        EinkStatus showImage(const std::vector<EinkFrame> &updateFrames,
                             const EinkFrame &refreshFrame,
                             const std::uint8_t *frameBuffer,
                             const EinkRefreshMode refreshMode) override;
        void prepareEarlyRequest(EinkRefreshMode refreshMode, const WaveformTemperature behaviour) override;

        EinkStatus resetAndInit() override;
        EinkStatus dither() override;
        EinkStatus powerOn() override;
        EinkStatus powerOff() override;
        EinkStatus shutdown() override;
        EinkStatus wipeOut() override;
        EinkStatus reinitAndPowerOn() override;
        explicit EinkDisplay(FrameSize size);

        ~EinkDisplay() noexcept override;

        auto setMode(EinkDisplayColorMode mode) noexcept -> void override;
        [[nodiscard]] auto getMode() const noexcept -> EinkDisplayColorMode override;

        auto showImageUpdate(const std::vector<EinkFrame> &updateFrames, const std::uint8_t *frameBuffer)
            -> EinkStatus override;
        auto showImageRefresh(const EinkFrame &refreshFrame, EinkRefreshMode refreshMode) -> EinkStatus override;
        auto showImage(const std::vector<EinkFrame> &updateFrames,
                       const EinkFrame &refreshFrame,
                       const std::uint8_t *frameBuffer,
                       EinkRefreshMode refreshMode) -> EinkStatus override;
        auto prepareEarlyRequest(EinkRefreshMode refreshMode, WaveformTemperature behaviour) -> void override;

        [[nodiscard]] auto resetAndInit() -> EinkStatus override;
        [[nodiscard]] auto dither() -> EinkStatus override;
        [[nodiscard]] auto powerOn() -> EinkStatus override;
        [[nodiscard]] auto powerOff() -> EinkStatus override;
        [[nodiscard]] auto shutdown() -> EinkStatus override;
        [[nodiscard]] auto wipeOut() -> EinkStatus override;
        [[nodiscard]] auto reinitAndPowerOn() -> EinkStatus override;

        [[nodiscard]] auto getDevice() const noexcept -> std::shared_ptr<devices::Device> override;

      private:
        bool isNewWaveformNeeded(const EinkWaveforms_e newMode, const int32_t newTemperature) const;
        void resetWaveformSettings();

        EinkBpp_e getCurrentBitsPerPixelFormat() const noexcept;
        [[nodiscard]] auto isNewWaveformNeeded(bsp::eink::EinkWaveform newMode, std::int32_t newTemperature) const
            -> bool;
        [[nodiscard]] auto setWaveform(bsp::eink::EinkWaveform mode, std::int32_t temperature) -> EinkStatus;
        auto resetWaveformSettings() -> void;

        EinkStatus setWaveform(const EinkWaveforms_e mode, const std::int32_t temperature);
        [[nodiscard]] auto getCurrentBitsPerPixelFormat() const noexcept -> bsp::eink::EinkBpp;

        std::int32_t getLastTemperature() const noexcept;
        [[nodiscard]] auto getLastTemperature() const noexcept -> std::int32_t;

        EinkStatus updateDisplay(EinkFrame frame, const std::uint8_t *frameBuffer);
        EinkStatus refreshDisplay(EinkFrame frame, const EinkRefreshMode refreshMode);
        EinkStatus prepareDisplay(const EinkRefreshMode refreshMode, const WaveformTemperature behaviour);
        EinkStatus tryReinitAndPowerOn();
        auto updateDisplay(EinkFrame frame, const std::uint8_t *frameBuffer) -> EinkStatus;
        auto refreshDisplay(EinkFrame frame) -> EinkStatus;
        auto prepareDisplay(EinkRefreshMode refreshMode, WaveformTemperature behaviour) -> EinkStatus;
        auto tryReinitAndPowerOn() -> EinkStatus;

        FrameSize size;

        EinkWaveformSettings_t currentWaveform;
        bsp::eink::EinkWaveformSettings currentWaveform;
        EinkDisplayColorMode displayMode;

        std::shared_ptr<drivers::DriverLPSPI> driverLPSPI;

D module-bsp/board/rt1051/bsp/eink/bsp_eink.cpp => module-bsp/board/rt1051/bsp/eink/bsp_eink.cpp +0 -491
@@ 1,491 0,0 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#include "bsp_eink.h"

#include "board.h"
#include "fsl_lpspi.h"
#include "fsl_lpspi_edma.h"

#include "dma_config.h"
#include "bsp/eink/eink_gpio.hpp"

#include "FreeRTOS.h"
#include "semphr.h"

#include "drivers/dmamux/DriverDMAMux.hpp"
#include "drivers/dma/DriverDMA.hpp"
#include "drivers/gpio/DriverGPIO.hpp"
#include "board/BoardDefinitions.hpp"

#define BSP_EINK_LPSPI_PCS_TO_SCK_DELAY       1000
#define BSP_EINK_LPSPI_SCK_TO_PSC_DELAY       1000
#define BSP_EINK_LPSPI_BETWEEN_TRANSFER_DELAY 1000
#define BSP_EINK_LPSPI_MASTER_PCS_PIN_SEL     (kLPSPI_MasterPcs0)
#define BSP_EINK_LPSPI_SLAVE_PCS_PIN_SEL      (kLPSPI_SlavePcs0)

#define BSP_EINK_LPSPI_BASE BOARD_EINK_LPSPI_BASE

#define BSP_EINK_TRANSFER_WRITE_CLOCK 18000000
#define BSP_EINK_TRANSFER_READ_CLOCK  3000000

using namespace drivers;

typedef enum
{
    EventWaitRegistered,
    EventWaitNotRegistered
} busy_wait_registered_e;

typedef const struct _lpspi_edma_resource
{
    DMA_Type *txEdmaBase;
    std::uint32_t txEdmaChannel;
    std::uint8_t txDmaRequest;

    DMA_Type *rxEdmaBase;
    std::uint32_t rxEdmaChannel;
    std::uint8_t rxDmaRequest;

#if (defined(FSL_FEATURE_SOC_DMAMUX_COUNT) && FSL_FEATURE_SOC_DMAMUX_COUNT)
    DMAMUX_Type *txDmamuxBase;
    DMAMUX_Type *rxDmamuxBase;
#endif
} lpspi_edma_resource_t;

typedef const struct _lpspi_resource
{
    LPSPI_Type *base;
    std::uint32_t instance;
    std::uint32_t (*GetFreq)(void);
} lpspi_resource_t;

typedef struct _bsp_eink_driver
{
    lpspi_resource_t *resource;
    lpspi_edma_resource_t *dmaResource;
    lpspi_master_edma_handle_t *handle;
    edma_handle_t *edmaRxRegToRxDataHandle;
    edma_handle_t *edmaTxDataToTxRegHandle;
    std::uint32_t baudRate_Bps;
    std::uint8_t flags; // Control and state flags.

    bsp_eink_BusyEvent event;
    eink_spi_cs_config_e chipselectConf;  // Current transfer chip select configuration(automatic of manual)
    busy_wait_registered_e eventRegister; // Tells if something is waiting for not busy event

} bsp_eink_driver_t;

namespace
{
    lpspi_master_config_t spi_config;
    std::shared_ptr<DriverGPIO> gpio;
    std::shared_ptr<DriverDMA> dma;
    std::shared_ptr<DriverDMAMux> dmamux;
    std::unique_ptr<DriverDMAHandle> rxDMAHandle;
    std::unique_ptr<DriverDMAHandle> txDMAHandle;

    constexpr auto delayInNanoSec = 1'000'000'000 / BSP_EINK_TRANSFER_WRITE_CLOCK;
} // namespace

static std::uint32_t BSP_EINK_LPSPI_GetFreq(void)
{
    return GetPerphSourceClock(PerphClock_LPSPI);
}

lpspi_resource_t BSP_EINK_LPSPI_Resource = {BSP_EINK_LPSPI_BASE, 1, BSP_EINK_LPSPI_GetFreq};

lpspi_edma_resource_t BSP_EINK_LPSPI_EdmaResource = {
    BSP_EINK_LPSPI_DMA_TX_DMA_BASE,
    BSP_EINK_LPSPI_DMA_TX_CH,
    BSP_EINK_LPSPI_DMA_TX_PERI_SEL,
    BSP_EINK_LPSPI_DMA_RX_DMA_BASE,
    BSP_EINK_LPSPI_DMA_RX_CH,
    BSP_EINK_LPSPI_DMA_RX_PERI_SEL,

    BSP_EINK_LPSPI_DMA_TX_DMAMUX_BASE,
    BSP_EINK_LPSPI_DMA_RX_DMAMUX_BASE,
};

AT_NONCACHEABLE_SECTION(lpspi_master_edma_handle_t BSP_EINK_LPSPI_EdmaHandle);

static bsp_eink_driver_t BSP_EINK_LPSPI_EdmaDriverState = {
    &BSP_EINK_LPSPI_Resource,
    &BSP_EINK_LPSPI_EdmaResource,
    &BSP_EINK_LPSPI_EdmaHandle,
    nullptr, // will be filled in init function
    nullptr, // will be filled in init function
    0,
    0,
    0,
    SPI_AUTOMATIC_CS,
    EventWaitRegistered,
};

static bool isEInkInitialised = false;
static SemaphoreHandle_t bsp_eink_TransferComplete;
static SemaphoreHandle_t bsp_eink_busySemaphore; // This semaphore suspends the task until the EPD display is busy

static void s_LPSPI_MasterEdmaCallback(LPSPI_Type *base,
                                       lpspi_master_edma_handle_t *handle,
                                       status_t status,
                                       void *userData)
{
    BaseType_t xHigherPriorityTaskWoken = pdFALSE;

    // bsp_eink_driver_t* driver = (bsp_eink_driver_t*)userData;

    if (xQueueSendFromISR(bsp_eink_TransferComplete, &status, &xHigherPriorityTaskWoken) != pdPASS) {
        // if here sth really bad happened
        return;
    }

    // Disable SPI for current consumption reducing
    LPSPI_Enable(BSP_EINK_LPSPI_BASE, false);

    portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
}

status_t BSP_EinkInit()
{
    if (isEInkInitialised) {
        return kStatus_Success;
    }
    bsp_eink_driver_t *lpspi = &BSP_EINK_LPSPI_EdmaDriverState;
    // lpspi_edma_resource_t *dmaResource = lpspi->dmaResource;

    // If was already created - free it
    if (bsp_eink_busySemaphore != NULL) {
        vSemaphoreDelete(bsp_eink_busySemaphore);
    }

    // Create new semaphore
    bsp_eink_busySemaphore = xSemaphoreCreateBinary();
    if (bsp_eink_busySemaphore == NULL) {
        return kStatus_Fail;
    }

    // At the beginning the semaphore is in unknown state and it has to clearly taken or given
    xSemaphoreTake(bsp_eink_busySemaphore, 0);

    // If was already created - free it
    if (bsp_eink_TransferComplete != NULL) {
        vQueueDelete(bsp_eink_TransferComplete);
    }

    // Create new queue
    bsp_eink_TransferComplete = xQueueCreate(1, sizeof(std::uint32_t));
    if (bsp_eink_TransferComplete == NULL) {
        vSemaphoreDelete(bsp_eink_busySemaphore);
        bsp_eink_busySemaphore = NULL;
        return kStatus_Fail;
    }

    lpspi->eventRegister = EventWaitNotRegistered;

    gpio = DriverGPIO::Create(static_cast<GPIOInstances>(BoardDefinitions::EINK_GPIO), DriverGPIOParams{});

    bsp::eink::eink_gpio_configure();

    LPSPI_MasterGetDefaultConfig(&spi_config);

    spi_config.baudRate                      = BSP_EINK_TRANSFER_WRITE_CLOCK;
    spi_config.bitsPerFrame                  = 8;
    spi_config.cpol                          = kLPSPI_ClockPolarityActiveHigh;
    spi_config.cpha                          = kLPSPI_ClockPhaseFirstEdge;
    spi_config.direction                     = kLPSPI_MsbFirst;
    spi_config.pcsToSckDelayInNanoSec        = delayInNanoSec;
    spi_config.lastSckToPcsDelayInNanoSec    = delayInNanoSec;
    spi_config.betweenTransferDelayInNanoSec = delayInNanoSec;
    spi_config.whichPcs                      = kLPSPI_Pcs0;
    spi_config.pcsActiveHighOrLow            = kLPSPI_PcsActiveLow;
    spi_config.pinCfg                        = kLPSPI_SdiInSdoOut;
    spi_config.dataOutConfig                 = kLpspiDataOutRetained;

    LPSPI_MasterInit(BSP_EINK_LPSPI_BASE, &spi_config, BSP_EINK_LPSPI_GetFreq());

    // fsl lpspi doesn't support configuring autopcs feature
    BSP_EINK_LPSPI_BASE->CFGR1 |= LPSPI_CFGR1_AUTOPCS(0);

    dmamux = DriverDMAMux::Create(static_cast<DMAMuxInstances>(BoardDefinitions::EINK_DMAMUX), DriverDMAMuxParams{});
    dma    = DriverDMA::Create(static_cast<DMAInstances>(BoardDefinitions::EINK_DMA), DriverDMAParams{});

    txDMAHandle = dma->CreateHandle(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL));
    rxDMAHandle = dma->CreateHandle(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL));
    dmamux->Enable(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL),
                   BSP_EINK_LPSPI_DMA_TX_PERI_SEL); // TODO: M.P fix BSP_EINK_LPSPI_DMA_TX_PERI_SEL
    dmamux->Enable(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL),
                   BSP_EINK_LPSPI_DMA_RX_PERI_SEL); // TODO: M.P fix BSP_EINK_LPSPI_DMA_RX_PERI_SEL

    BSP_EINK_LPSPI_EdmaDriverState.edmaTxDataToTxRegHandle =
        reinterpret_cast<edma_handle_t *>(txDMAHandle->GetHandle());
    BSP_EINK_LPSPI_EdmaDriverState.edmaRxRegToRxDataHandle =
        reinterpret_cast<edma_handle_t *>(rxDMAHandle->GetHandle());

    LPSPI_SetMasterSlaveMode(BSP_EINK_LPSPI_BASE, kLPSPI_Master);
    LPSPI_MasterTransferCreateHandleEDMA(BSP_EINK_LPSPI_BASE,
                                         lpspi->handle,
                                         s_LPSPI_MasterEdmaCallback,
                                         NULL,
                                         lpspi->edmaRxRegToRxDataHandle,
                                         lpspi->edmaTxDataToTxRegHandle);

    isEInkInitialised = true;
    return kStatus_Success;
}

void BSP_EinkDeinit(void)
{
    if (!isEInkInitialised) {
        return;
    }
    LPSPI_Enable(BSP_EINK_LPSPI_BASE, false);

    if (bsp_eink_busySemaphore != NULL) {
        vSemaphoreDelete(bsp_eink_busySemaphore);
        bsp_eink_busySemaphore = NULL;
    }

    if (bsp_eink_TransferComplete != NULL) {
        vQueueDelete(bsp_eink_TransferComplete);
        bsp_eink_TransferComplete = NULL;
    }

    dmamux->Disable(static_cast<std::uint32_t>(BoardDefinitions::EINK_TX_DMA_CHANNEL));
    dmamux->Disable(static_cast<std::uint32_t>(BoardDefinitions::EINK_RX_DMA_CHANNEL));
    dmamux.reset();
    dma.reset();

    gpio->DisableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    gpio.reset();

    isEInkInitialised = false;
}

void BSP_EinkLogicPowerOn()
{
    bsp::eink::eink_gpio_power_on();
}

void BSP_EinkLogicPowerOff()
{
    bsp::eink::eink_gpio_power_off();
}

status_t BSP_EinkChangeSpiFrequency(std::uint32_t frequencyHz)
{
    std::uint32_t tcrPrescalerValue = 0;

    LPSPI_Enable(BSP_EINK_LPSPI_BASE, false);
    LPSPI_MasterSetBaudRate(BSP_EINK_LPSPI_BASE, frequencyHz, BSP_EINK_LPSPI_GetFreq(), &tcrPrescalerValue);

    spi_config.baudRate      = frequencyHz;
    BSP_EINK_LPSPI_BASE->TCR = LPSPI_TCR_CPOL(spi_config.cpol) | LPSPI_TCR_CPHA(spi_config.cpha) |
                               LPSPI_TCR_LSBF(spi_config.direction) | LPSPI_TCR_FRAMESZ(spi_config.bitsPerFrame - 1U) |
                               LPSPI_TCR_PRESCALE(tcrPrescalerValue) | LPSPI_TCR_PCS(spi_config.whichPcs);

    return 0;
}

status_t BSP_EinkWriteData(void *txBuffer, std::uint32_t len, eink_spi_cs_config_e cs)
{
    constexpr std::uint32_t TX_TIMEOUT_MS = 2000;
    status_t tx_status                    = -1;
    status_t status;
    lpspi_transfer_t xfer = {};

    if (cs == SPI_AUTOMATIC_CS) {
        BSP_EinkWriteCS(BSP_Eink_CS_Clr);
    }

    const std::uint8_t loopCnt = (len / (DMA_MAX_SINGLE_TRANSACTION_PAYLOAD + 1)) + 1;
    std::uint32_t frameSize    = 0;
    std::uint32_t bytesSent    = 0;

    // Increase the SPI frequency to the SPI WRITE value
    BSP_EinkChangeSpiFrequency(BSP_EINK_TRANSFER_WRITE_CLOCK);

    BSP_EINK_LPSPI_EdmaDriverState.chipselectConf   = cs;
    BSP_EINK_LPSPI_EdmaDriverState.handle->userData = &BSP_EINK_LPSPI_EdmaDriverState;

    // Clean the TX complete queue
    xQueueReset(bsp_eink_TransferComplete);
    // Clear the BUSY Pin IRQ Flag
    gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    // Enable the BUSY Pin IRQ
    gpio->EnableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    // Take the BUSY semaphore without timeout just in case the transmission makes the BUSY pin state change. It
    // enables the driver to block then on the bsp_eink_busySemaphore until the BUSY pin is deasserted
    xSemaphoreTake(bsp_eink_busySemaphore, 0);

    // The MAJOR loop of the DMA can be maximum of value 32767
    for (std::uint8_t i = 0; i < loopCnt; ++i) {
        if (len > DMA_MAX_SINGLE_TRANSACTION_PAYLOAD) {
            frameSize = DMA_MAX_SINGLE_TRANSACTION_PAYLOAD;
        }
        else {
            frameSize = len;
        }

        xfer.rxData      = NULL;
        xfer.txData      = (std::uint8_t *)txBuffer + bytesSent;
        xfer.dataSize    = frameSize;
        xfer.configFlags = /*RTE_SPI1_MASTER_PCS_PIN_SEL |*/ kLPSPI_MasterByteSwap | kLPSPI_MasterPcsContinuous;

        SCB_CleanInvalidateDCache();
        status = LPSPI_MasterTransferEDMA(
            BSP_EINK_LPSPI_EdmaDriverState.resource->base, BSP_EINK_LPSPI_EdmaDriverState.handle, &xfer);
        if (status != kStatus_Success) {
            // in case of error just flush transfer complete queue
            xQueueReset(bsp_eink_TransferComplete);

            if (cs == SPI_AUTOMATIC_CS) {
                BSP_EinkWriteCS(BSP_Eink_CS_Set);
            }
            return status;
        }
        else {
            if (xQueueReceive(bsp_eink_TransferComplete, &tx_status, pdMS_TO_TICKS(TX_TIMEOUT_MS)) != pdPASS) {
                // sth really bad happened
                if (cs == SPI_AUTOMATIC_CS) {
                    BSP_EinkWriteCS(BSP_Eink_CS_Set);
                }
                return -1;
            }
        }

        bytesSent += frameSize;
        len -= frameSize;
    }

    if (cs == SPI_AUTOMATIC_CS) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
    }
    return tx_status;
}

status_t BSP_EinkReadData(void *rxBuffer, std::uint32_t len, eink_spi_cs_config_e cs)
{
    const int RX_TIMEOUT_MS = 2000;
    status_t tx_status      = -1;
    status_t status;
    lpspi_transfer_t xfer = {};

    xfer.txData      = NULL;
    xfer.rxData      = (std::uint8_t *)rxBuffer;
    xfer.dataSize    = len;
    xfer.configFlags = kLPSPI_MasterByteSwap | kLPSPI_MasterPcsContinuous;

    if (cs == SPI_AUTOMATIC_CS) {
        BSP_EinkWriteCS(BSP_Eink_CS_Clr);
    }

    // Slow down the SPI clock for the value proper for the read operation
    BSP_EinkChangeSpiFrequency(BSP_EINK_TRANSFER_READ_CLOCK);

    BSP_EINK_LPSPI_EdmaDriverState.chipselectConf   = cs;
    BSP_EINK_LPSPI_EdmaDriverState.handle->userData = &BSP_EINK_LPSPI_EdmaDriverState;

    // Clean the TX complete queue
    xQueueReset(bsp_eink_TransferComplete);
    // Clear the BUSY Pin IRQ Flag
    gpio->ClearPortInterrupts(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    // Enable the BUSY Pin IRQ
    gpio->EnableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));
    // Take the BUSY semaphore without timeout just in case the transmission makes the BUSY pin state change. It
    // enables the driver to block then on the bsp_eink_busySemaphore until the BUSY pin is deasserted
    xSemaphoreTake(bsp_eink_busySemaphore, 0);

    status = LPSPI_MasterTransferEDMA(
        BSP_EINK_LPSPI_EdmaDriverState.resource->base, BSP_EINK_LPSPI_EdmaDriverState.handle, &xfer);
    if (status != kStatus_Success) {
        // in case of error just flush transfer complete queue
        std::uint32_t dummy = 0;
        xQueueReceive(bsp_eink_TransferComplete, &dummy, 0);
        if (cs == SPI_AUTOMATIC_CS) {
            BSP_EinkWriteCS(BSP_Eink_CS_Set);
        }

        return status;
    }
    else {
        if (xQueueReceive(bsp_eink_TransferComplete, &tx_status, pdMS_TO_TICKS(RX_TIMEOUT_MS)) != pdPASS) {
            // sth really bad happened
            if (cs == SPI_AUTOMATIC_CS) {
                BSP_EinkWriteCS(BSP_Eink_CS_Set);
            }

            return -1;
        }
    }

    if (cs == SPI_AUTOMATIC_CS) {
        BSP_EinkWriteCS(BSP_Eink_CS_Set);
    }

    return tx_status;
}

std::uint8_t BSP_EinkWaitUntilDisplayBusy(std::uint32_t timeout)
{
    std::uint8_t ret                             = 0;
    BSP_EINK_LPSPI_EdmaDriverState.eventRegister = EventWaitRegistered;
    if (xSemaphoreTake(bsp_eink_busySemaphore, timeout) != pdPASS) {
        ret = 0;
    }
    else {
        xSemaphoreGive(bsp_eink_busySemaphore);
        ret = 1;
    }

    BSP_EINK_LPSPI_EdmaDriverState.eventRegister = EventWaitNotRegistered;
    return ret;
}

void BSP_EinkResetDisplayController(void)
{
    BSP_EinkWriteCS(BSP_Eink_CS_Set);

    gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_RESET_PIN), 0);
    vTaskDelay(10);
    gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_RESET_PIN), 1);
    vTaskDelay(10);
}

void BSP_EinkWriteCS(bsp_eink_cs_ctrl_t ctrl)
{
    if (ctrl == BSP_Eink_CS_Clr) {
        gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_CS_PIN), 0);
    }
    else if (ctrl == BSP_Eink_CS_Set) {
        gpio->WritePin(static_cast<std::uint32_t>(BoardDefinitions::EINK_CS_PIN), 1);
    }
}

BaseType_t BSP_EinkBusyPinStateChangeHandler(void)
{
    BaseType_t xHigherPriorityTaskWoken = pdFALSE;

    // Give semaphore only if something is waiting on it
    if (BSP_EINK_LPSPI_EdmaDriverState.eventRegister == EventWaitRegistered) {
        gpio->DisableInterrupt(1 << static_cast<std::uint32_t>(BoardDefinitions::EINK_BUSY_PIN));

        if (xSemaphoreGiveFromISR(bsp_eink_busySemaphore, &xHigherPriorityTaskWoken) != pdPASS) {
            // shouldn't get here!
        }

        // call user defined "eink not busy" event
        if (BSP_EINK_LPSPI_EdmaDriverState.event) {
            BSP_EINK_LPSPI_EdmaDriverState.event();
        }
    }

    /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
      exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
    __DSB();
#endif

    return xHigherPriorityTaskWoken;
}

D module-bsp/board/rt1051/bsp/eink/bsp_eink.h => module-bsp/board/rt1051/bsp/eink/bsp_eink.h +0 -52
@@ 1,52 0,0 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#ifndef EINK_BSP_EINK_H_
#define EINK_BSP_EINK_H_

#include <cstdint>
#include "fsl_common.h"
#include "FreeRTOS.h"

#ifdef __cplusplus
extern "C"
{
#endif

    typedef enum
    {
        SPI_AUTOMATIC_CS,
        SPI_MANUAL_CS
    } eink_spi_cs_config_e;

    typedef enum
    {
        BSP_Eink_CS_Clr = 0,
        BSP_Eink_CS_Set = 1
    } bsp_eink_cs_ctrl_t;

    typedef void (*bsp_eink_BusyEvent)(void);

    inline constexpr auto BSP_EinkBusyTimeout = 3000U;

    status_t BSP_EinkInit();
    void BSP_EinkDeinit(void);

    void BSP_EinkLogicPowerOn();
    void BSP_EinkLogicPowerOff();

    void BSP_EinkWriteCS(bsp_eink_cs_ctrl_t ctrl);
    std::uint8_t BSP_EinkWaitUntilDisplayBusy(std::uint32_t timeout);
    void BSP_EinkResetDisplayController(void);

    status_t BSP_EinkChangeSpiFrequency(uint32_t frequencyHz);
    status_t BSP_EinkWriteData(void *txBuffer, uint32_t len, eink_spi_cs_config_e cs);
    status_t BSP_EinkReadData(void *rxBuffer, uint32_t len, eink_spi_cs_config_e cs);

    BaseType_t BSP_EinkBusyPinStateChangeHandler(void);

#ifdef __cplusplus
}
#endif

#endif /* EINK_BSP_EINK_H_ */

D module-bsp/board/rt1051/bsp/eink/eink_binarization_luts.h => module-bsp/board/rt1051/bsp/eink/eink_binarization_luts.h +0 -7
@@ 1,7 0,0 @@
// Copyright (c) 2017-2024, Mudita Sp. z.o.o. All rights reserved.
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#include <stdint-gcc.h>

extern const uint8_t einkBinarizationLUT_2bpp[256];
extern const uint8_t einkBinarizationLUT_4bpp[256];

M module-bsp/board/rt1051/puretx/eink-config.h => module-bsp/board/rt1051/puretx/eink-config.h +2 -1
@@ 2,6 2,7 @@
// For licensing, see https://github.com/mudita/MuditaOS/blob/master/LICENSE.md

#pragma once

#define BOARD_EINK_DISPLAY_RES_X 480
#define BOARD_EINK_DISPLAY_RES_Y 600
#define EINK_ROTATE_90_CLOCKWISE 1
#define EINK_ROTATE_90_CLOCKWISE

M module-bsp/board/rt1051/puretx/irq_gpio.cpp => module-bsp/board/rt1051/puretx/irq_gpio.cpp +10 -11
@@ 8,7 8,7 @@
#include <fsl_common.h>
#include <fsl_rtwdog.h>

#include "board/rt1051/bsp/eink/bsp_eink.h"
#include "board/rt1051/bsp/eink/BspEink.hpp"
#include <hal/key_input/KeyInput.hpp>
#include <hal/battery_charger/BatteryChargerIRQ.hpp>
#include <log/log.hpp>


@@ 17,7 17,7 @@

namespace bsp
{
    void irq_gpio_Init(void)
    void irq_gpio_Init()
    {
        DisableIRQ(GPIO1_Combined_0_15_IRQn);
        DisableIRQ(GPIO1_Combined_16_31_IRQn);


@@ 59,7 59,7 @@ namespace bsp
        void GPIO1_Combined_0_15_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO1);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO1);

            if (irq_mask & (1 << BSP_CELLULAR_STATUS_PIN)) {
                xHigherPriorityTaskWoken |= cellular::status::statusIRQhandler();


@@ 75,7 75,7 @@ namespace bsp
        void GPIO1_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO1);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO1);

            if (irq_mask & (1 << BSP_BLUETOOTH_UART_CTS_PIN)) {
                LOG_DEBUG("CTS IRQ!");


@@ 91,7 91,7 @@ namespace bsp
        void GPIO2_Combined_0_15_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO2);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO2);

            if (irq_mask & (1 << BOARD_KEYBOARD_RF_BUTTON_PIN)) {
                xHigherPriorityTaskWoken |= hal::key_input::rightFunctionalIRQHandler();


@@ 115,7 115,7 @@ namespace bsp
        void GPIO2_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO2);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO2);

            if (irq_mask & (1 << BOARD_KEYBOARD_IRQ_GPIO_PIN)) {
                xHigherPriorityTaskWoken |= hal::key_input::generalIRQHandler(irq_mask);


@@ 143,11 143,10 @@ namespace bsp
        void GPIO3_Combined_16_31_IRQHandler(void)
        {
            BaseType_t xHigherPriorityTaskWoken = 0;
            uint32_t irq_mask                   = GPIO_GetPinsInterruptFlags(GPIO3);
            std::uint32_t irq_mask              = GPIO_GetPinsInterruptFlags(GPIO3);

            if (irq_mask & (1 << BOARD_EINK_BUSY_GPIO_PIN)) {

                xHigherPriorityTaskWoken |= BSP_EinkBusyPinStateChangeHandler();
                xHigherPriorityTaskWoken |= bsp::eink::busyPinStateChangeHandler();
            }

            // Clear all IRQs on the GPIO3 port


@@ 170,11 169,11 @@ namespace bsp
         * Get the value of last PC state and store in non-volatile SNVS register
         * to have any data that can be used to debug if program died in IRQ or
         * critical section and neither log nor crashdump was created. */
        __attribute__((used, noreturn)) void RTWDOG_Handler(const uint32_t *sp)
        __attribute__((used, noreturn)) void RTWDOG_Handler(const std::uint32_t *sp)
        {
            RTWDOG_ClearStatusFlags(RTWDOG, kRTWDOG_InterruptFlag);

            const uint32_t pc = sp[6];
            const std::uint32_t pc = sp[6];
            SNVS->LPGPR[1]    = pc;

            while (true) {}; // Wait for RTWDOG to reset the board

M module-bsp/hal/include/hal/eink/AbstractEinkDisplay.hpp => module-bsp/hal/include/hal/eink/AbstractEinkDisplay.hpp +25 -27
@@ 10,7 10,6 @@

namespace hal::eink
{

    enum class EinkDisplayColorMode
    {
        EinkDisplayColorModeStandard,


@@ 19,8 18,8 @@ namespace hal::eink

    enum class WaveformTemperature
    {
        KEEP_CURRENT,
        MEASURE_NEW,
        KeepCurrent,
        MeasureNew
    };

    enum class EinkRefreshMode


@@ 41,20 40,19 @@ namespace hal::eink
        EinkTimeout,               //!< Timeout occured while waiting for not busy signal from EINK
        EinkNoMem,                 //!< Could not allocate memory
        EinkWaveformsFileOpenFail, //!< Could not open the file with the waveforms for EPD display

        EinkUnknown,
        EinkUnknown
    };

    struct FrameSize
    {
        uint16_t width;
        uint16_t height;
        std::uint16_t width;
        std::uint16_t height;
    };

    struct EinkFrame
    {
        uint16_t pos_x;
        uint16_t pos_y;
        std::uint16_t pos_x;
        std::uint16_t pos_y;
        FrameSize size;
    };



@@ 68,24 66,24 @@ namespace hal::eink

        virtual ~AbstractEinkDisplay() = default;

        virtual void setMode(const EinkDisplayColorMode mode) noexcept                                        = 0;
        virtual EinkDisplayColorMode getMode() const noexcept                                                 = 0;
        virtual EinkStatus showImageUpdate(const std::vector<EinkFrame> &updateFrames,
                                           const std::uint8_t *frameBuffer)                                   = 0;
        virtual EinkStatus showImageRefresh(const EinkFrame &refreshFrame, const EinkRefreshMode refreshMode) = 0;
        virtual EinkStatus showImage(const std::vector<EinkFrame> &updateFrames,
                                     const EinkFrame &refreshFrame,
                                     const std::uint8_t *frameBuffer,
                                     const EinkRefreshMode refreshMode)                                       = 0;
        virtual void prepareEarlyRequest(EinkRefreshMode refreshMode, const WaveformTemperature behaviour)    = 0;
        virtual auto setMode(EinkDisplayColorMode mode) noexcept -> void            = 0;
        [[nodiscard]] virtual auto getMode() const noexcept -> EinkDisplayColorMode = 0;
        virtual auto showImageUpdate(const std::vector<EinkFrame> &updateFrames, const std::uint8_t *frameBuffer)
            -> EinkStatus                                                                                       = 0;
        virtual auto showImageRefresh(const EinkFrame &refreshFrame, EinkRefreshMode refreshMode) -> EinkStatus = 0;
        virtual auto showImage(const std::vector<EinkFrame> &updateFrames,
                               const EinkFrame &refreshFrame,
                               const std::uint8_t *frameBuffer,
                               EinkRefreshMode refreshMode) -> EinkStatus                                       = 0;
        virtual auto prepareEarlyRequest(EinkRefreshMode refreshMode, WaveformTemperature behaviour) -> void    = 0;

        virtual EinkStatus dither()                                         = 0;
        virtual EinkStatus powerOn()                                        = 0;
        virtual EinkStatus powerOff()                                       = 0;
        virtual EinkStatus shutdown()                                       = 0;
        virtual EinkStatus wipeOut()                                        = 0;
        virtual EinkStatus resetAndInit()                                   = 0;
        virtual std::shared_ptr<devices::Device> getDevice() const noexcept = 0;
        virtual EinkStatus reinitAndPowerOn()                               = 0;
        virtual auto dither() -> EinkStatus                                                       = 0;
        virtual auto powerOn() -> EinkStatus                                                      = 0;
        virtual auto powerOff() -> EinkStatus                                                     = 0;
        virtual auto shutdown() -> EinkStatus                                                     = 0;
        virtual auto wipeOut() -> EinkStatus                                                      = 0;
        virtual auto resetAndInit() -> EinkStatus                                                 = 0;
        [[nodiscard]] virtual auto getDevice() const noexcept -> std::shared_ptr<devices::Device> = 0;
        virtual auto reinitAndPowerOn() -> EinkStatus                                             = 0;
    };
} // namespace hal::eink

M module-services/service-eink/ServiceEink.cpp => module-services/service-eink/ServiceEink.cpp +1 -1
@@ 461,7 461,7 @@ namespace service::eink
    {
        const auto waveformUpdateMsg = static_cast<service::eink::PrepareDisplayEarlyRequest *>(message);
        display->prepareEarlyRequest(translateToEinkRefreshMode(waveformUpdateMsg->getRefreshMode()),
                                     hal::eink::WaveformTemperature::MEASURE_NEW);
                                     hal::eink::WaveformTemperature::MeasureNew);
        return sys::MessageNone{};
    }


M module-services/service-eink/board/rt1051/EinkIncludes.hpp => module-services/service-eink/board/rt1051/EinkIncludes.hpp +1 -1
@@ 3,7 3,7 @@

#pragma once

#include <board/rt1051/bsp/eink/ED028TC1.h>
#include <board/rt1051/bsp/eink/ED028TC1.hpp>
#include <chip.hpp>

extern "C"