From bf76415c7c34be08b2f607e40ab089fa42ebb4ec Mon Sep 17 00:00:00 2001 From: Jozsef Kiraly <371847+fonix232@users.noreply.github.com> Date: Mon, 27 Oct 2025 14:20:14 +0000 Subject: [PATCH 1/2] feat: Add M5Stack PaperS3 support --- .gitmodules | 3 + CMakeLists.txt | 1 + Devices/m5stack-papers3/CMakeLists.txt | 7 + .../m5stack-papers3/Source/Configuration.cpp | 86 ++++ Devices/m5stack-papers3/Source/Init.cpp | 20 + .../Source/devices/Display.cpp | 26 + .../Source/devices/Display.hpp | 11 + .../m5stack-papers3/Source/devices/Power.cpp | 261 ++++++++++ .../m5stack-papers3/Source/devices/Power.hpp | 58 +++ .../m5stack-papers3/Source/devices/SdCard.cpp | 21 + .../m5stack-papers3/Source/devices/SdCard.hpp | 8 + Devices/m5stack-papers3/device.properties | 22 + Drivers/EPDiyDisplay/CMakeLists.txt | 6 + Drivers/EPDiyDisplay/README.md | 3 + Drivers/EPDiyDisplay/Source/EpdiyDisplay.cpp | 444 ++++++++++++++++++ Drivers/EPDiyDisplay/Source/EpdiyDisplay.h | 154 ++++++ .../EPDiyDisplay/Source/EpdiyDisplayHelper.h | 42 ++ .../Source/ChargeFromAdcVoltage.h | 10 + Firmware/Kconfig | 4 +- Libraries/epdiy | 1 + 20 files changed, 1187 insertions(+), 1 deletion(-) create mode 100644 Devices/m5stack-papers3/CMakeLists.txt create mode 100644 Devices/m5stack-papers3/Source/Configuration.cpp create mode 100644 Devices/m5stack-papers3/Source/Init.cpp create mode 100644 Devices/m5stack-papers3/Source/devices/Display.cpp create mode 100644 Devices/m5stack-papers3/Source/devices/Display.hpp create mode 100644 Devices/m5stack-papers3/Source/devices/Power.cpp create mode 100644 Devices/m5stack-papers3/Source/devices/Power.hpp create mode 100644 Devices/m5stack-papers3/Source/devices/SdCard.cpp create mode 100644 Devices/m5stack-papers3/Source/devices/SdCard.hpp create mode 100644 Devices/m5stack-papers3/device.properties create mode 100644 Drivers/EPDiyDisplay/CMakeLists.txt create mode 100644 Drivers/EPDiyDisplay/README.md create mode 100644 Drivers/EPDiyDisplay/Source/EpdiyDisplay.cpp create mode 100644 Drivers/EPDiyDisplay/Source/EpdiyDisplay.h create mode 100644 Drivers/EPDiyDisplay/Source/EpdiyDisplayHelper.h create mode 160000 Libraries/epdiy diff --git a/.gitmodules b/.gitmodules index 0d18c27c6..75e195998 100644 --- a/.gitmodules +++ b/.gitmodules @@ -16,3 +16,6 @@ [submodule "Libraries/cJSON/cJSON"] path = Libraries/cJSON/cJSON url = https://github.com/DaveGamble/cJSON.git +[submodule "Libraries/epdiy"] + path = Libraries/epdiy + url = https://github.com/fonix232/epdiy diff --git a/CMakeLists.txt b/CMakeLists.txt index 7355c21af..70035f67d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,6 +39,7 @@ if (DEFINED ENV{ESP_IDF_VERSION}) "TactilityCore" "Libraries/esp_lvgl_port" "Libraries/elf_loader" + "Libraries/epdiy" "Libraries/lvgl" "Libraries/lv_screenshot" "Libraries/minitar" diff --git a/Devices/m5stack-papers3/CMakeLists.txt b/Devices/m5stack-papers3/CMakeLists.txt new file mode 100644 index 000000000..0ed967803 --- /dev/null +++ b/Devices/m5stack-papers3/CMakeLists.txt @@ -0,0 +1,7 @@ +file(GLOB_RECURSE SOURCE_FILES Source/*.c*) + +idf_component_register( + SRCS ${SOURCE_FILES} + INCLUDE_DIRS "Source" + REQUIRES Tactility esp_lvgl_port EPDiyDisplay GT911 driver esp_adc EstimatedPower vfs fatfs +) diff --git a/Devices/m5stack-papers3/Source/Configuration.cpp b/Devices/m5stack-papers3/Source/Configuration.cpp new file mode 100644 index 000000000..713ed8430 --- /dev/null +++ b/Devices/m5stack-papers3/Source/Configuration.cpp @@ -0,0 +1,86 @@ +#include +#include +#include +#include + +#include "devices/Display.hpp" +#include "devices/Power.hpp" +#include "devices/SdCard.hpp" + +bool initBoot(); + +using namespace tt::hal; + +static std::vector> createDevices() { + return { + createPower(), + createDisplay(), + createSdCard() + }; +} + +extern const Configuration hardwareConfiguration = { + .initBoot = initBoot, + .createDevices = createDevices, + .i2c = { + i2c::Configuration { + .name = "Internal", + .port = I2C_NUM_0, + .initMode = i2c::InitMode::ByTactility, + .isMutable = false, + .config = (i2c_config_t) { + .mode = I2C_MODE_MASTER, + .sda_io_num = GPIO_NUM_41, + .scl_io_num = GPIO_NUM_42, + .sda_pullup_en = true, + .scl_pullup_en = true, + .master = { + .clk_speed = 400000 + }, + .clk_flags = 0 + } + }, + i2c::Configuration { + .name = "External", + .port = I2C_NUM_1, + .initMode = i2c::InitMode::Disabled, + .isMutable = true, + .config = (i2c_config_t) { + .mode = I2C_MODE_MASTER, + .sda_io_num = GPIO_NUM_2, + .scl_io_num = GPIO_NUM_1, + .sda_pullup_en = false, + .scl_pullup_en = false, + .master = { + .clk_speed = 400000 + }, + .clk_flags = 0 + } + } + }, + .spi = { + spi::Configuration { + .device = SPI2_HOST, + .dma = SPI_DMA_CH_AUTO, + .config = { + .mosi_io_num = GPIO_NUM_38, + .miso_io_num = GPIO_NUM_40, + .sclk_io_num = GPIO_NUM_39, + .quadwp_io_num = GPIO_NUM_NC, // Quad SPI LCD driver is not yet supported + .quadhd_io_num = GPIO_NUM_NC, // Quad SPI LCD driver is not yet supported + .data4_io_num = GPIO_NUM_NC, + .data5_io_num = GPIO_NUM_NC, + .data6_io_num = GPIO_NUM_NC, + .data7_io_num = GPIO_NUM_NC, + .data_io_default_level = false, + .max_transfer_sz = 0, + .flags = 0, + .isr_cpu_id = ESP_INTR_CPU_AFFINITY_AUTO, + .intr_flags = 0 + }, + .initMode = spi::InitMode::ByTactility, + .isMutable = false, + .lock = nullptr + } + }, +}; diff --git a/Devices/m5stack-papers3/Source/Init.cpp b/Devices/m5stack-papers3/Source/Init.cpp new file mode 100644 index 000000000..44b438d64 --- /dev/null +++ b/Devices/m5stack-papers3/Source/Init.cpp @@ -0,0 +1,20 @@ +#include "Tactility/kernel/SystemEvents.h" + +#include + +#define TAG "papers3" + +static bool powerOn() { + // No power on sequence needed for M5Stack PaperS3 + return true; +} + +bool initBoot() { + ESP_LOGI(TAG, LOG_MESSAGE_POWER_ON_START); + if (!powerOn()) { + TT_LOG_E(TAG, LOG_MESSAGE_POWER_ON_FAILED); + return false; + } + + return true; +} diff --git a/Devices/m5stack-papers3/Source/devices/Display.cpp b/Devices/m5stack-papers3/Source/devices/Display.cpp new file mode 100644 index 000000000..b6879c978 --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/Display.cpp @@ -0,0 +1,26 @@ +#include "Display.hpp" + +#include +#include + + +static std::shared_ptr createTouch() { + // Note for future changes: Interrupt pin is 48, reset is NC + auto configuration = std::make_unique( + I2C_NUM_0, + PAPERS3_EPD_HORIZONTAL_RESOLUTION,// yMax - PaperS3 is rotated + PAPERS3_EPD_VERTICAL_RESOLUTION, // xMax - PaperS3 is rotated + true, // swapXY + true, // mirrorX + false, // mirrorY + GPIO_NUM_NC, + GPIO_NUM_48 + ); + + return std::make_shared(std::move(configuration)); +} + +std::shared_ptr createDisplay() { + auto touch = createTouch(); + return EpdiyDisplayHelper::createM5PaperS3Display(touch); +} diff --git a/Devices/m5stack-papers3/Source/devices/Display.hpp b/Devices/m5stack-papers3/Source/devices/Display.hpp new file mode 100644 index 000000000..7770b65d7 --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/Display.hpp @@ -0,0 +1,11 @@ +#pragma once + +#include +#include +#include + +// Display +#define PAPERS3_EPD_HORIZONTAL_RESOLUTION 540 +#define PAPERS3_EPD_VERTICAL_RESOLUTION 960 + +std::shared_ptr createDisplay(); diff --git a/Devices/m5stack-papers3/Source/devices/Power.cpp b/Devices/m5stack-papers3/Source/devices/Power.cpp new file mode 100644 index 000000000..6b2f7d73e --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/Power.cpp @@ -0,0 +1,261 @@ +#include "Power.hpp" + +#include +#include +#include +#include +#include + +using namespace tt::hal::power; + +constexpr auto* TAG = "PaperS3Power"; + +// M5Stack PaperS3 hardware pin definitions +constexpr gpio_num_t VBAT_PIN = GPIO_NUM_3; // Battery voltage with 2x divider +constexpr adc_channel_t VBAT_ADC_CHANNEL = ADC_CHANNEL_2; // GPIO3 = ADC1_CHANNEL_2 + +constexpr gpio_num_t CHARGE_STATUS_PIN = GPIO_NUM_4; // Charge status analog signal +constexpr adc_channel_t CHARGE_STATUS_ADC_CHANNEL = ADC_CHANNEL_3; // GPIO4 = ADC1_CHANNEL_3 + +constexpr gpio_num_t POWER_OFF_PIN = GPIO_NUM_44; // Pull high to trigger shutdown + +// Battery voltage divider ratio (voltage is divided by 2) +constexpr float VOLTAGE_DIVIDER_MULTIPLIER = 2.0f; + +// Battery voltage range for LiPo batteries +constexpr float MIN_BATTERY_VOLTAGE = 3.3f; // Minimum safe voltage +constexpr float MAX_BATTERY_VOLTAGE = 4.2f; // Maximum charge voltage + +// Charge status voltage threshold +// When not charging: ~0.01V (10mV) +// When charging: ~0.25-0.3V (250-300mV) +constexpr int CHARGING_VOLTAGE_THRESHOLD_MV = 100; + +// Power-off signal timing +constexpr int POWER_OFF_PULSE_COUNT = 5; // Number of pulses to ensure shutdown +constexpr int POWER_OFF_PULSE_DURATION_MS = 100; // Duration of each pulse + +PaperS3Power::PaperS3Power( + std::unique_ptr chargeFromAdcVoltage, + adc_oneshot_unit_handle_t adcHandle, + adc_channel_t chargeStatusAdcChannel, + gpio_num_t powerOffPin +) + : chargeFromAdcVoltage(std::move(chargeFromAdcVoltage)), + adcHandle(adcHandle), + chargeStatusAdcChannel(chargeStatusAdcChannel), + powerOffPin(powerOffPin) { + + TT_LOG_I(TAG, "Initialized M5Stack PaperS3 power management"); + TT_LOG_I(TAG, " Battery voltage: GPIO%d (ADC1_CH%d)", VBAT_PIN, VBAT_ADC_CHANNEL); + TT_LOG_I(TAG, " Charge status: GPIO%d (ADC1_CH%d)", CHARGE_STATUS_PIN, chargeStatusAdcChannel); + TT_LOG_I(TAG, " Power off: GPIO%d", powerOffPin); +} + +PaperS3Power::~PaperS3Power() { + // GPIO will be cleaned up by system + TT_LOG_I(TAG, "Power management shut down"); +} + +void PaperS3Power::initializeChargeStatus() { + if (chargeStatusInitialized) { + return; + } + + // Configure the charge status ADC channel + adc_oneshot_chan_cfg_t config = { + .atten = ADC_ATTEN_DB_12, // 12dB attenuation for wider range + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + + esp_err_t err = adc_oneshot_config_channel(adcHandle, chargeStatusAdcChannel, &config); + if (err != ESP_OK) { + TT_LOG_E(TAG, "Failed to configure charge status ADC channel: %s", esp_err_to_name(err)); + return; + } + + chargeStatusInitialized = true; + TT_LOG_I(TAG, "Charge status monitoring initialized"); +} + +void PaperS3Power::initializePowerOff() { + if (powerOffInitialized) { + return; + } + + // Configure power-off pin as output, initially low + gpio_config_t io_conf = { + .pin_bit_mask = (1ULL << powerOffPin), + .mode = GPIO_MODE_OUTPUT, + .pull_up_en = GPIO_PULLUP_DISABLE, + .pull_down_en = GPIO_PULLDOWN_DISABLE, + .intr_type = GPIO_INTR_DISABLE, + }; + + esp_err_t err = gpio_config(&io_conf); + if (err != ESP_OK) { + TT_LOG_E(TAG, "Failed to configure power-off pin GPIO%d: %s", powerOffPin, esp_err_to_name(err)); + return; + } + + gpio_set_level(powerOffPin, 0); // Start low + + powerOffInitialized = true; + TT_LOG_I(TAG, "Power-off control initialized on GPIO%d", powerOffPin); +} + +bool PaperS3Power::isCharging() { + if (!chargeStatusInitialized) { + initializeChargeStatus(); + if (!chargeStatusInitialized) { + return false; + } + } + + int adc_raw = 0; + esp_err_t ret = adc_oneshot_read(adcHandle, chargeStatusAdcChannel, &adc_raw); + + if (ret != ESP_OK) { + TT_LOG_E(TAG, "Failed to read charge status ADC: %s", esp_err_to_name(ret)); + return false; + } + + // Convert raw ADC value to voltage (approximate) + // For 12-bit ADC with 12dB attenuation: 0-4095 maps to roughly 0-3100mV + int voltage_mv = 0; + static adc_cali_handle_t s_cali = nullptr; + if (!s_cali) { + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = ADC_UNIT_1, + .chan = CHARGE_STATUS_ADC_CHANNEL, + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }; + if (adc_cali_create_scheme_curve_fitting(&cali_config, &s_cali) != ESP_OK) { + TT_LOG_W(TAG, "ADC calibration unavailable; falling back to rough conversion"); + } + } + if (s_cali && adc_cali_raw_to_voltage(s_cali, adc_raw, &voltage_mv) != ESP_OK) { + TT_LOG_W(TAG, "Calibration failed; falling back to rough conversion"); + voltage_mv = (adc_raw * 3100) / 4095; + } else if (!s_cali) { + voltage_mv = (adc_raw * 3100) / 4095; + } + + bool charging = voltage_mv > CHARGING_VOLTAGE_THRESHOLD_MV; + + TT_LOG_D(TAG, "Charge status: raw=%d, voltage=%dmV, charging=%s", + adc_raw, voltage_mv, charging ? "YES" : "NO"); + + return charging; +} + +bool PaperS3Power::supportsMetric(MetricType type) const { + switch (type) { + using enum MetricType; + case BatteryVoltage: + case ChargeLevel: + case IsCharging: + return true; + default: + return false; + } +} + +bool PaperS3Power::getMetric(MetricType type, MetricData& data) { + switch (type) { + using enum MetricType; + + case BatteryVoltage: + return chargeFromAdcVoltage->readBatteryVoltageSampled(data.valueAsUint32); + + case ChargeLevel: { + uint32_t voltage = 0; + if (chargeFromAdcVoltage->readBatteryVoltageSampled(voltage)) { + data.valueAsUint8 = chargeFromAdcVoltage->estimateChargeLevelFromVoltage(voltage); + return true; + } + return false; + } + + case IsCharging: + data.valueAsBool = isCharging(); + return true; + + default: + return false; + } +} + +void PaperS3Power::powerOff() { + TT_LOG_W(TAG, "Power-off requested"); + + if (!powerOffInitialized) { + initializePowerOff(); + if (!powerOffInitialized) { + TT_LOG_E(TAG, "Power-off failed: GPIO not initialized"); + return; + } + } + + TT_LOG_W(TAG, "Triggering shutdown via GPIO%d (sending %d pulses)...", + powerOffPin, POWER_OFF_PULSE_COUNT); + + // Send multiple high pulses to ensure shutdown is triggered + for (int i = 0; i < POWER_OFF_PULSE_COUNT; i++) { + gpio_set_level(powerOffPin, 1); // Pull high + vTaskDelay(pdMS_TO_TICKS(POWER_OFF_PULSE_DURATION_MS)); + gpio_set_level(powerOffPin, 0); // Pull low + vTaskDelay(pdMS_TO_TICKS(POWER_OFF_PULSE_DURATION_MS)); + } + + // Final high state + gpio_set_level(powerOffPin, 1); + + TT_LOG_W(TAG, "Shutdown signal sent. Waiting for power-off..."); + + // If we're still running after a delay, log it + vTaskDelay(pdMS_TO_TICKS(1000)); + TT_LOG_E(TAG, "Device did not power off as expected"); +} + +std::shared_ptr createPower() { + // Configure ChargeFromAdcVoltage for battery voltage monitoring + ChargeFromAdcVoltage::Configuration config = { + .adcMultiplier = VOLTAGE_DIVIDER_MULTIPLIER, + .adcRefVoltage = 3.3f, // ESP32-S3 reference voltage + .adcChannel = VBAT_ADC_CHANNEL, + .adcConfig = { + .unit_id = ADC_UNIT_1, + .clk_src = ADC_RTC_CLK_SRC_DEFAULT, + .ulp_mode = ADC_ULP_MODE_DISABLE, + }, + .adcChannelConfig = { + .atten = ADC_ATTEN_DB_12, + .bitwidth = ADC_BITWIDTH_DEFAULT, + }, + }; + + // Create ChargeFromAdcVoltage with battery voltage range + auto chargeFromAdcVoltage = std::make_unique( + config, + MIN_BATTERY_VOLTAGE, + MAX_BATTERY_VOLTAGE + ); + + // Get ADC handle to share with charge status monitoring + adc_oneshot_unit_handle_t adcHandle = chargeFromAdcVoltage->getAdcHandle(); + + if (adcHandle == nullptr) { + TT_LOG_E(TAG, "Failed to get ADC handle"); + return nullptr; + } + + // Create and return PaperS3Power instance + return std::make_shared( + std::move(chargeFromAdcVoltage), + adcHandle, + CHARGE_STATUS_ADC_CHANNEL, + POWER_OFF_PIN + ); +} diff --git a/Devices/m5stack-papers3/Source/devices/Power.hpp b/Devices/m5stack-papers3/Source/devices/Power.hpp new file mode 100644 index 000000000..ba306d0bd --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/Power.hpp @@ -0,0 +1,58 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace tt::hal::power { + +/** + * @brief Power management for M5Stack PaperS3 + * + * Hardware configuration: + * - Battery voltage: GPIO3 (ADC1_CHANNEL_2) with 2x voltage divider + * - Charge status: GPIO4 (ADC1_CHANNEL_3) - analog signal + * * ~0.01V when not charging + * * ~0.25-0.3V when charging + * - Power off: GPIO44 - pull high to trigger shutdown + */ +class PaperS3Power final : public PowerDevice { +private: + std::unique_ptr<::ChargeFromAdcVoltage> chargeFromAdcVoltage; + adc_oneshot_unit_handle_t adcHandle; + adc_channel_t chargeStatusAdcChannel; + gpio_num_t powerOffPin; + bool chargeStatusInitialized = false; + bool powerOffInitialized = false; + +public: + explicit PaperS3Power( + std::unique_ptr<::ChargeFromAdcVoltage> chargeFromAdcVoltage, + adc_oneshot_unit_handle_t adcHandle, + adc_channel_t chargeStatusAdcChannel, + gpio_num_t powerOffPin + ); + ~PaperS3Power() override; + + std::string getName() const override { return "M5Stack PaperS3 Power"; } + std::string getDescription() const override { return "Battery monitoring with charge detection and power-off"; } + + // Metric support + bool supportsMetric(MetricType type) const override; + bool getMetric(MetricType type, MetricData& data) override; + + // Power off support + bool supportsPowerOff() const override { return true; } + void powerOff() override; + +private: + void initializeChargeStatus(); + void initializePowerOff(); + bool isCharging(); +}; + +} // namespace tt::hal::power + +std::shared_ptr createPower(); diff --git a/Devices/m5stack-papers3/Source/devices/SdCard.cpp b/Devices/m5stack-papers3/Source/devices/SdCard.cpp new file mode 100644 index 000000000..1c1346e6b --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/SdCard.cpp @@ -0,0 +1,21 @@ +#include "SdCard.hpp" + +#include + +constexpr auto PAPERS3_SDCARD_PIN_CS = GPIO_NUM_47; + +using tt::hal::sdcard::SpiSdCardDevice; + +std::shared_ptr createSdCard() { + auto configuration = std::make_unique( + PAPERS3_SDCARD_PIN_CS, + GPIO_NUM_NC, + GPIO_NUM_NC, + GPIO_NUM_NC, + SdCardDevice::MountBehaviour::AtBoot + ); + + return std::make_shared( + std::move(configuration) + ); +} diff --git a/Devices/m5stack-papers3/Source/devices/SdCard.hpp b/Devices/m5stack-papers3/Source/devices/SdCard.hpp new file mode 100644 index 000000000..b282a3222 --- /dev/null +++ b/Devices/m5stack-papers3/Source/devices/SdCard.hpp @@ -0,0 +1,8 @@ +#pragma once + +#include +#include "Tactility/hal/sdcard/SdCardDevice.h" + +using tt::hal::sdcard::SdCardDevice; + +std::shared_ptr createSdCard(); diff --git a/Devices/m5stack-papers3/device.properties b/Devices/m5stack-papers3/device.properties new file mode 100644 index 000000000..587bede54 --- /dev/null +++ b/Devices/m5stack-papers3/device.properties @@ -0,0 +1,22 @@ +[general] +vendor=M5Stack +name=PaperS3 +incubating=true + +[hardware] +target=ESP32S3 +flashSize=16MB +spiRam=true +spiRamMode=OCT +spiRamSpeed=120M +tinyUsb=true +esptoolFlashFreq=120M + + +[display] +size=5.4" +shape=rectangle +dpi=234 + +[lvgl] +colorDepth=4 diff --git a/Drivers/EPDiyDisplay/CMakeLists.txt b/Drivers/EPDiyDisplay/CMakeLists.txt new file mode 100644 index 000000000..559cb99b4 --- /dev/null +++ b/Drivers/EPDiyDisplay/CMakeLists.txt @@ -0,0 +1,6 @@ +idf_component_register( + SRC_DIRS "Source" + INCLUDE_DIRS "Source" + REQUIRES Tactility epdiy esp_lvgl_port + PRIV_REQUIRES esp_timer +) diff --git a/Drivers/EPDiyDisplay/README.md b/Drivers/EPDiyDisplay/README.md new file mode 100644 index 000000000..5d53d805c --- /dev/null +++ b/Drivers/EPDiyDisplay/README.md @@ -0,0 +1,3 @@ +# EPDiy Display Driver + +A display driver for e-paper/e-ink displays using the EPDiy library. This driver provides LVGL integration and high-level display management for EPD panels. diff --git a/Drivers/EPDiyDisplay/Source/EpdiyDisplay.cpp b/Drivers/EPDiyDisplay/Source/EpdiyDisplay.cpp new file mode 100644 index 000000000..0db149108 --- /dev/null +++ b/Drivers/EPDiyDisplay/Source/EpdiyDisplay.cpp @@ -0,0 +1,444 @@ +#include "EpdiyDisplay.h" + +#include +#include + +#include +#include +#include + +constexpr const char* TAG = "EpdiyDisplay"; + +EpdiyDisplay::EpdiyDisplay(std::unique_ptr inConfiguration) + : configuration(std::move(inConfiguration)), + lock(std::make_shared()) +{ + tt_check(configuration != nullptr); + tt_check(configuration->board != nullptr); + tt_check(configuration->display != nullptr); +} + +EpdiyDisplay::~EpdiyDisplay() { + if (lvglDisplay != nullptr) { + stopLvgl(); + } + if (initialized) { + stop(); + } +} + +bool EpdiyDisplay::start() { + if (initialized) { + TT_LOG_W(TAG, "Already initialized"); + return true; + } + + // Initialize EPDiy + epd_init( + configuration->board, + configuration->display, + configuration->initOptions + ); + + // Set rotation BEFORE initializing highlevel state + epd_set_rotation(configuration->rotation); + TT_LOG_I(TAG, "Display rotation set to %d", configuration->rotation); + + // Initialize the high-level API + highlevelState = epd_hl_init(configuration->waveform); + if (highlevelState.front_fb == nullptr) { + TT_LOG_E(TAG, "Failed to initialize EPDiy highlevel state"); + epd_deinit(); + return false; + } + + framebuffer = epd_hl_get_framebuffer(&highlevelState); + + initialized = true; + TT_LOG_I(TAG, "EPDiy initialized successfully (%dx%d native, %dx%d rotated)", + epd_width(), epd_height(), + epd_rotated_display_width(), epd_rotated_display_height()); + + // Perform initial clear to ensure clean state + TT_LOG_I(TAG, "Performing initial screen clear..."); + clearScreen(); + TT_LOG_I(TAG, "Screen cleared"); + + return true; +} + +bool EpdiyDisplay::stop() { + if (!initialized) { + return true; + } + + if (lvglDisplay != nullptr) { + stopLvgl(); + } + + // Power off the display + if (powered) { + setPowerOn(false); + } + + // Note: EPDiy highlevel state buffers are allocated in PSRAM + // and will be freed when the system shuts down + // We don't have an explicit cleanup function for highlevel state + + // Deinitialize EPDiy + epd_deinit(); + + initialized = false; + TT_LOG_I(TAG, "EPDiy deinitialized"); + + return true; +} + +void EpdiyDisplay::setPowerOn(bool turnOn) { + if (powered == turnOn) { + return; + } + + if (turnOn) { + epd_poweron(); + powered = true; + TT_LOG_D(TAG, "EPD power on"); + } else { + epd_poweroff(); + powered = false; + TT_LOG_D(TAG, "EPD power off"); + } +} + +// LVGL functions +bool EpdiyDisplay::startLvgl() { + if (lvglDisplay != nullptr) { + TT_LOG_W(TAG, "LVGL already initialized"); + return true; + } + + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized, call start() first"); + return false; + } + + // Get the native display dimensions + uint16_t width = epd_width(); + uint16_t height = epd_height(); + + TT_LOG_I(TAG, "Creating LVGL display: %dx%d (EPDiy rotation: %d)", width, height, configuration->rotation); + + // Create LVGL display with native dimensions + lvglDisplay = lv_display_create(width, height); + if (lvglDisplay == nullptr) { + TT_LOG_E(TAG, "Failed to create LVGL display"); + return false; + } + + // EPD uses 4-bit grayscale (16 levels) + // Map to LVGL's L8 format (8-bit grayscale) + lv_display_set_color_format(lvglDisplay, LV_COLOR_FORMAT_L8); + auto lv_rotation = epdRotationToLvgl(configuration->rotation); + lv_display_set_rotation(lvglDisplay, lv_rotation); + + // Allocate draw buffer + // EPDiy already allocates a buffer, so we only need one + size_t draw_buffer_size = width * height; + + // Allocate in SPIRAM if available, otherwise internal RAM + lvglDrawBuffer = static_cast(heap_caps_malloc(draw_buffer_size, MALLOC_CAP_SPIRAM | MALLOC_CAP_8BIT)); + if (lvglDrawBuffer == nullptr) { + lvglDrawBuffer = static_cast(heap_caps_malloc(draw_buffer_size, MALLOC_CAP_DMA | MALLOC_CAP_INTERNAL)); + } + + if (lvglDrawBuffer == nullptr) { + TT_LOG_E(TAG, "Failed to allocate draw buffer 1"); + lv_display_delete(lvglDisplay); + lvglDisplay = nullptr; + return false; + } + + // For EPD, we want full refresh mode based on configuration + lv_display_render_mode_t render_mode = configuration->fullRefresh + ? LV_DISPLAY_RENDER_MODE_FULL + : LV_DISPLAY_RENDER_MODE_PARTIAL; + + lv_display_set_buffers(lvglDisplay, lvglDrawBuffer, NULL, draw_buffer_size, render_mode); + + // Set flush callback + lv_display_set_flush_cb(lvglDisplay, flushCallback); + lv_display_set_user_data(lvglDisplay, this); + + // Register rotation change event callback + lv_display_add_event_cb(lvglDisplay, rotationEventCallback, LV_EVENT_RESOLUTION_CHANGED, this); + TT_LOG_D(TAG, "Registered rotation change event callback"); + + // Start touch device if present + auto touch_device = getTouchDevice(); + if (touch_device != nullptr && touch_device->supportsLvgl()) { + TT_LOG_D(TAG, "Starting touch device for LVGL"); + if (!touch_device->startLvgl(lvglDisplay)) { + TT_LOG_W(TAG, "Failed to start touch device for LVGL"); + } + } + + TT_LOG_I(TAG, "LVGL display initialized"); + return true; +} + +bool EpdiyDisplay::stopLvgl() { + if (lvglDisplay == nullptr) { + return false; + } + + TT_LOG_I(TAG, "Stopping LVGL display"); + + // Stop touch device + auto touch_device = getTouchDevice(); + if (touch_device != nullptr) { + touch_device->stopLvgl(); + } + + // Free draw buffer + if (lvglDrawBuffer != nullptr) { + heap_caps_free(lvglDrawBuffer); + lvglDrawBuffer = nullptr; + } + + // Delete display (this will automatically free the buffers) + lv_display_delete(lvglDisplay); + lvglDisplay = nullptr; + + + TT_LOG_I(TAG, "LVGL display stopped"); + return true; +} + +void EpdiyDisplay::flushCallback(lv_display_t* display, const lv_area_t* area, uint8_t* pixelMap) { + uint64_t t0 = esp_timer_get_time(); + auto* instance = static_cast(lv_display_get_user_data(display)); + if (instance != nullptr) { + instance->flushInternal(area, pixelMap); + } + TT_LOG_I(TAG, "flush took %llu us", (unsigned long long)(esp_timer_get_time() - t0)); + lv_display_flush_ready(display); +} + + +// EPD functions +void EpdiyDisplay::clearScreen() { + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized"); + return; + } + + std::lock_guard guard(*lock); + + if (!powered) { + setPowerOn(true); + } + + epd_clear(); + + // Also clear the framebuffer + epd_hl_set_all_white(&highlevelState); +} + +void EpdiyDisplay::clearArea(EpdRect area) { + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized"); + return; + } + + std::lock_guard guard(*lock); + + if (!powered) { + setPowerOn(true); + } + + epd_clear_area(area); +} + +enum EpdDrawError EpdiyDisplay::updateScreen(enum EpdDrawMode mode, int temperature) { + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized"); + return EPD_DRAW_FAILED_ALLOC; + } + + std::lock_guard guard(*lock); + + if (!powered) { + setPowerOn(true); + } + + // Use defaults if not specified + if (mode == MODE_UNKNOWN_WAVEFORM) { + mode = configuration->defaultDrawMode; + } + if (temperature == -1) { + temperature = configuration->defaultTemperature; + } + + return epd_hl_update_screen(&highlevelState, mode, temperature); +} + +enum EpdDrawError EpdiyDisplay::updateArea(EpdRect area, enum EpdDrawMode mode, int temperature) { + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized"); + return EPD_DRAW_FAILED_ALLOC; + } + + std::lock_guard guard(*lock); + + if (!powered) { + setPowerOn(true); + } + + // Use defaults if not specified + if (mode == MODE_UNKNOWN_WAVEFORM) { + mode = configuration->defaultDrawMode; + } + if (temperature == -1) { + temperature = configuration->defaultTemperature; + } + + return epd_hl_update_area(&highlevelState, mode, temperature, area); +} + +void EpdiyDisplay::setAllWhite() { + if (!initialized) { + TT_LOG_E(TAG, "EPD not initialized"); + return; + } + + std::lock_guard guard(*lock); + epd_hl_set_all_white(&highlevelState); +} + +// Internal functions +void EpdiyDisplay::flushInternal(const lv_area_t* area, uint8_t* pixelMap) { + if (!initialized) { + TT_LOG_E(TAG, "Cannot flush - EPD not initialized"); + return; + } + + // Lock for thread safety + std::lock_guard guard(*lock); + + // LVGL area coordinates (already in the rotated coordinate space that LVGL uses) + int x = area->x1; + int y = area->y1; + int width = lv_area_get_width(area); + int height = lv_area_get_height(area); + + TT_LOG_D(TAG, "Flushing area: x=%d, y=%d, w=%d, h=%d", x, y, width, height); + + // Convert 8-bit grayscale to 4-bit and pack 2 pixels/byte with row padding + const int row_stride_bytes = (width + 1) / 2; // bytes per row + const size_t packedSize = static_cast(row_stride_bytes) * height; + std::vector pixelMap4bit(packedSize, 0); // Initialize with zeros + + // Pack pixels row by row to avoid skewing with odd widths + for (int row = 0; row < height; ++row) { + const uint8_t* src = pixelMap + static_cast(row) * width; + uint8_t* dst = pixelMap4bit.data() + static_cast(row) * row_stride_bytes; + for (int col = 0; col < width; col += 2) { + const uint8_t p0 = src[col] / 17; + const uint8_t p1 = (col + 1 < width) ? (src[col + 1] / 17) : 0; + // Pack two 4-bit pixels into one byte: p1 in upper nibble, p0 in lower nibble + dst[col / 2] = static_cast((p1 << 4) | p0); + } + } + + // Update the screen area + // Use the rotated coordinates for the update area as well + EpdRect update_area = { + .x = x, + .y = y, + .width = static_cast(width), + .height = static_cast(height) + }; + + epd_draw_rotated_image( + update_area, + pixelMap4bit.data(), + framebuffer + ); + + epd_hl_update_area( + &highlevelState, + static_cast(configuration->defaultDrawMode | MODE_PACKING_2PPB), + configuration->defaultTemperature, + update_area + ); +} + +lv_display_rotation_t EpdiyDisplay::epdRotationToLvgl(enum EpdRotation epdRotation) { + // Static lookup table for EPD -> LVGL rotation mapping + // EPDiy: LANDSCAPE = 0°, PORTRAIT = 90° CW, INVERTED_LANDSCAPE = 180°, INVERTED_PORTRAIT = 270° CW + // LVGL: 0 = 0°, 90 = 90° CW, 180 = 180°, 270 = 270° CW + static const lv_display_rotation_t rotationMap[] = { + LV_DISPLAY_ROTATION_0, // EPD_ROT_LANDSCAPE (0) + LV_DISPLAY_ROTATION_270, // EPD_ROT_PORTRAIT (1) - 90° CW in EPD is 270° in LVGL + LV_DISPLAY_ROTATION_180, // EPD_ROT_INVERTED_LANDSCAPE (2) + LV_DISPLAY_ROTATION_90 // EPD_ROT_INVERTED_PORTRAIT (3) - 270° CW in EPD is 90° in LVGL + }; + + // Validate input and return mapped value + if (epdRotation >= 0 && epdRotation < 4) { + return rotationMap[epdRotation]; + } + + // Default to landscape if invalid + return LV_DISPLAY_ROTATION_0; +} + +enum EpdRotation EpdiyDisplay::lvglRotationToEpd(lv_display_rotation_t lvglRotation) { + // Static lookup table for LVGL -> EPD rotation mapping + static const enum EpdRotation rotationMap[] = { + EPD_ROT_LANDSCAPE, // LV_DISPLAY_ROTATION_0 (0) + EPD_ROT_INVERTED_PORTRAIT, // LV_DISPLAY_ROTATION_90 (1) + EPD_ROT_INVERTED_LANDSCAPE, // LV_DISPLAY_ROTATION_180 (2) + EPD_ROT_PORTRAIT // LV_DISPLAY_ROTATION_270 (3) + }; + + // Validate input and return mapped value + if (lvglRotation >= LV_DISPLAY_ROTATION_0 && lvglRotation <= LV_DISPLAY_ROTATION_270) { + return rotationMap[lvglRotation]; + } + + // Default to landscape if invalid + return EPD_ROT_LANDSCAPE; +} + +void EpdiyDisplay::rotationEventCallback(lv_event_t* event) { + auto* display = static_cast(lv_event_get_user_data(event)); + if (display == nullptr) { + return; + } + + lv_display_t* lvgl_display = static_cast(lv_event_get_target(event)); + if (lvgl_display == nullptr) { + return; + } + + lv_display_rotation_t rotation = lv_display_get_rotation(lvgl_display); + display->handleRotationChange(rotation); +} + +void EpdiyDisplay::handleRotationChange(lv_display_rotation_t lvgl_rotation) { + // Map LVGL rotation to EPDiy rotation using lookup table + enum EpdRotation epd_rotation = lvglRotationToEpd(lvgl_rotation); + + // Update EPDiy rotation + TT_LOG_I(TAG, "LVGL rotation changed to %d, setting EPDiy rotation to %d", lvgl_rotation, epd_rotation); + epd_set_rotation(epd_rotation); + + // Update configuration to keep it in sync + configuration->rotation = epd_rotation; + + // Log the new dimensions + TT_LOG_I(TAG, "Display dimensions after rotation: %dx%d", + epd_rotated_display_width(), epd_rotated_display_height()); +} + diff --git a/Drivers/EPDiyDisplay/Source/EpdiyDisplay.h b/Drivers/EPDiyDisplay/Source/EpdiyDisplay.h new file mode 100644 index 000000000..57af82d08 --- /dev/null +++ b/Drivers/EPDiyDisplay/Source/EpdiyDisplay.h @@ -0,0 +1,154 @@ +#pragma once + +#include +#include +#include +#include + +#include +#include +#include +#include + +class EpdiyDisplay final : public tt::hal::display::DisplayDevice { + +public: + + class Configuration { + public: + Configuration( + const EpdBoardDefinition* board, + const EpdDisplay_t* display, + std::shared_ptr touch = nullptr, + enum EpdInitOptions initOptions = EPD_OPTIONS_DEFAULT, + const EpdWaveform* waveform = EPD_BUILTIN_WAVEFORM, + int defaultTemperature = 25, + enum EpdDrawMode defaultDrawMode = MODE_GL16, + bool fullRefresh = false, + enum EpdRotation rotation = EPD_ROT_LANDSCAPE + ) : board(board), + display(display), + touch(std::move(touch)), + initOptions(initOptions), + waveform(waveform), + defaultTemperature(defaultTemperature), + defaultDrawMode(defaultDrawMode), + fullRefresh(fullRefresh), + rotation(rotation) + {} + + const EpdBoardDefinition* board; + const EpdDisplay_t* display; + std::shared_ptr touch; + enum EpdInitOptions initOptions; + const EpdWaveform* waveform; + int defaultTemperature; + enum EpdDrawMode defaultDrawMode; + bool fullRefresh; + enum EpdRotation rotation; + }; + +private: + std::unique_ptr configuration; + std::shared_ptr lock; + lv_display_t* _Nullable lvglDisplay = nullptr; + EpdiyHighlevelState highlevelState = {}; + uint8_t* framebuffer = nullptr; + uint8_t* lvglDrawBuffer = nullptr; + bool initialized = false; + bool powered = false; + + static void flushCallback(lv_display_t* display, const lv_area_t* area, uint8_t* pixelMap); + void flushInternal(const lv_area_t* area, uint8_t* pixelMap); + + static void rotationEventCallback(lv_event_t* event); + void handleRotationChange(lv_display_rotation_t rotation); + + // Rotation mapping helpers + static lv_display_rotation_t epdRotationToLvgl(enum EpdRotation epdRotation); + static enum EpdRotation lvglRotationToEpd(lv_display_rotation_t lvglRotation); + +public: + + explicit EpdiyDisplay(std::unique_ptr inConfiguration); + + ~EpdiyDisplay() override; + + std::string getName() const override { return "EPDiy"; } + + std::string getDescription() const override { + return "E-Ink display powered by EPDiy library"; + } + + // Device lifecycle + bool start() override; + bool stop() override; + + // Power control + void setPowerOn(bool turnOn) override; + bool isPoweredOn() const override { return powered; } + bool supportsPowerControl() const override { return true; } + + // Touch device + std::shared_ptr _Nullable getTouchDevice() override { + return configuration->touch; + } + + // LVGL support + bool supportsLvgl() const override { return true; } + bool startLvgl() override; + bool stopLvgl() override; + lv_display_t* _Nullable getLvglDisplay() const override { return lvglDisplay; } + + // DisplayDriver (not supported for EPD) + bool supportsDisplayDriver() const override { return false; } + std::shared_ptr _Nullable getDisplayDriver() override { + return nullptr; + } + + // EPD specific functions + + /** + * Get a reference to the framebuffer + */ + uint8_t* getFramebuffer() { + return epd_hl_get_framebuffer(&highlevelState); + } + + /** + * Clear the screen by flashing it + */ + void clearScreen(); + + /** + * Clear an area by flashing it + */ + void clearArea(EpdRect area); + + /** + * Manually trigger a screen update + * @param mode The draw mode to use (defaults to configuration default) + * @param temperature Temperature in °C (defaults to configuration default) + */ + enum EpdDrawError updateScreen( + enum EpdDrawMode mode = MODE_UNKNOWN_WAVEFORM, + int temperature = -1 + ); + + /** + * Update a specific area of the screen + * @param area The area to update + * @param mode The draw mode to use (defaults to configuration default) + * @param temperature Temperature in °C (defaults to configuration default) + */ + enum EpdDrawError updateArea( + EpdRect area, + enum EpdDrawMode mode = MODE_UNKNOWN_WAVEFORM, + int temperature = -1 + ); + + /** + * Set the display to all white + */ + void setAllWhite(); +}; diff --git a/Drivers/EPDiyDisplay/Source/EpdiyDisplayHelper.h b/Drivers/EPDiyDisplay/Source/EpdiyDisplayHelper.h new file mode 100644 index 000000000..39fdd7f84 --- /dev/null +++ b/Drivers/EPDiyDisplay/Source/EpdiyDisplayHelper.h @@ -0,0 +1,42 @@ +#pragma once + +#include "EpdiyDisplay.h" +#include +#include +#include + +/** + * Helper class to create EPDiy displays with common configurations + */ +class EpdiyDisplayHelper { +public: + /** + * Create a display for M5Paper S3 + * @param touch Optional touch device + * @param temperature Display temperature in °C (default: 20) + * @param drawMode Default draw mode (default: MODE_GL16 for non-flashing updates) + * @param fullRefresh Use full refresh mode (default: false for partial updates) + * @param rotation Display rotation (default: EPD_ROT_LANDSCAPE) + */ + static std::shared_ptr createM5PaperS3Display( + std::shared_ptr touch = nullptr, + int temperature = 20, + enum EpdDrawMode drawMode = MODE_GL16, + bool fullRefresh = false, + enum EpdRotation rotation = EPD_ROT_LANDSCAPE + ) { + auto config = std::make_unique( + &epd_board_m5papers3, + &ED047TC1, + touch, + static_cast(EPD_LUT_1K | EPD_FEED_QUEUE_32), + static_cast(EPD_BUILTIN_WAVEFORM), + temperature, + drawMode, + fullRefresh, + rotation + ); + + return std::make_shared(std::move(config)); + } +}; diff --git a/Drivers/EstimatedPower/Source/ChargeFromAdcVoltage.h b/Drivers/EstimatedPower/Source/ChargeFromAdcVoltage.h index 3e96f3737..46de3e690 100644 --- a/Drivers/EstimatedPower/Source/ChargeFromAdcVoltage.h +++ b/Drivers/EstimatedPower/Source/ChargeFromAdcVoltage.h @@ -39,4 +39,14 @@ class ChargeFromAdcVoltage { bool readBatteryVoltageOnce(uint32_t& output) const; uint8_t estimateChargeLevelFromVoltage(uint32_t milliVolt) const { return chargeFromVoltage.estimateCharge(milliVolt); } + + /** + * @brief Get the ADC unit handle + * + * Exposes the ADC unit handle to allow configuring additional channels + * on the same ADC unit. Use with caution. + * + * @return The ADC unit handle, or nullptr if not initialized + */ + adc_oneshot_unit_handle_t getAdcHandle() const { return adcHandle; } }; diff --git a/Firmware/Kconfig b/Firmware/Kconfig index 871c980d4..5aed50513 100644 --- a/Firmware/Kconfig +++ b/Firmware/Kconfig @@ -63,7 +63,9 @@ menu "Tactility App" bool "M5Stack Core2" config TT_DEVICE_M5STACK_CORES3 bool "M5Stack CoreS3" - config TT_DEVICE_M5STACK_STICKC_PLUS + config TT_BOARD_M5STACK_PAPERS3 + bool "M5Stack PaperS3" + config TT_BOARD_M5STACK_STICKC_PLUS bool "M5Stack StickC Plus" config TT_DEVICE_M5STACK_STICKC_PLUS2 bool "M5Stack StickC Plus2" diff --git a/Libraries/epdiy b/Libraries/epdiy new file mode 160000 index 000000000..5050a739b --- /dev/null +++ b/Libraries/epdiy @@ -0,0 +1 @@ +Subproject commit 5050a739b67fe1159f82c12224e9429e49e69992 From 510e9f466c95f9256337b9317f619ff24dab8eba Mon Sep 17 00:00:00 2001 From: Jozsef Kiraly <371847+fonix232@users.noreply.github.com> Date: Sun, 16 Nov 2025 21:29:38 +0000 Subject: [PATCH 2/2] fix: Add UART config --- .../m5stack-papers3/Source/Configuration.cpp | 25 +++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/Devices/m5stack-papers3/Source/Configuration.cpp b/Devices/m5stack-papers3/Source/Configuration.cpp index 713ed8430..1bef1a457 100644 --- a/Devices/m5stack-papers3/Source/Configuration.cpp +++ b/Devices/m5stack-papers3/Source/Configuration.cpp @@ -83,4 +83,29 @@ extern const Configuration hardwareConfiguration = { .lock = nullptr } }, + .uart = { + uart::Configuration { + .name = "External", + .port = UART_NUM_1, + .rxPin = GPIO_NUM_2, + .txPin = GPIO_NUM_1, + .rtsPin = GPIO_NUM_NC, + .ctsPin = GPIO_NUM_NC, + .rxBufferSize = 1024, + .txBufferSize = 1024, + .config = { + .baud_rate = 115200, + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, + .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, + .rx_flow_ctrl_thresh = 0, + .source_clk = UART_SCLK_DEFAULT, + .flags = { + .allow_pd = 0, + .backup_before_sleep = 0, + } + } + } + } };